发表于 2021-2-22 17:06:38
2382 浏览 3 回复
offboard模式切换
本帖最后由 zqqqqqqq7 于 2021-2-22 20:28 编辑
我使用树莓派+pixhawk2.4.8的组合运行px4 v1.11.3的固件,想通过mavros控制小车以一定的线速度和角速度运行。在官方示例的基础上修改的下列代码,在实机测试时offboard切换不成功,换成官方代码就可以切换offboard成功。想请教一下问题出现在哪里?
我自己也查了一下有大神的解答如下,但是没有太明白“在设置offboard的的while()中也需要不断的发布位姿信 息 ”这个应该添加到哪里?
#include <ros/ros.h>
#include <geometry_msgs/Twist.h>
#include <mavros_msgs/CommandBool.h>
#include <mavros_msgs/SetMode.h>
#include <mavros_msgs/State.h>
mavros_msgs::State current_state;
void state_cb(const mavros_msgs::State::ConstPtr& msg){
current_state = *msg;
}
int main(int argc, char **argv)
{
ros::init(argc, argv, "offb_node");
ros::NodeHandle nh;
ros::Subscriber state_sub = nh.subscribe<mavros_msgs::State>
("mavros/state", 10, state_cb);
ros::Publisher local_pos_pub = nh.advertise<geometry_msgs::Twist>
("mavros/setpoint_position/cmd_vel", 10);
ros::ServiceClient arming_client = nh.serviceClient<mavros_msgs::CommandBool>
("mavros/cmd/arming");
ros::ServiceClient set_mode_client = nh.serviceClient<mavros_msgs::SetMode>
("mavros/set_mode");
ros::Rate rate(20.0);
while(ros::ok() && current_state.connected){
ros::spinOnce();
rate.sleep();
}
geometry_msgs::Twist twist;
twist.linear.x = 1;
twist.angular.z = 0.5;
mavros_msgs::SetMode offb_set_mode;
offb_set_mode.request.custom_mode = "OFFBOARD";
mavros_msgs::CommandBool arm_cmd;
arm_cmd.request.value = true;
ros::Time last_request = ros::Time::now();
while(ros::ok()){
if( current_state.mode != "OFFBOARD" &&
(ros::Time::now() - last_request > ros::Duration(5.0))){
if( set_mode_client.call(offb_set_mode) &&
offb_set_mode.response.mode_sent){
ROS_INFO("OFFBOARD enabled");
}
last_request = ros::Time::now();
} else {
if( !current_state.armed &&
(ros::Time::now() - last_request > ros::Duration(5.0))){
if( arming_client.call(arm_cmd) &&
arm_cmd.response.success){
ROS_INFO("Vehicle armed");
}
last_request = ros::Time::now();
}
}
local_pos_pub.publish(twist);
ros::spinOnce();
rate.sleep();
}
return 0;
}
eason已获得悬赏 3 阿木币 最佳答案
mavros/setpoint_position/cmd_vel,应该是mavros/setpoint_velocity/cmd_vel
我看了一下px4 rover,支持的还是84那个mavlink消息,支持发位置速度,好像还有姿态
本帖子中包含更多资源
您需要 登录 才可以下载或查看,没有帐号?立即注册
x
扫一扫浏览分享
发表于 2021-2-22 18:09:38
官方代码的发布位姿信息的代码在哪儿啊 你看到了吗?首先发布位姿信息的代码,你可以先标注出来。
楼主|
发表于 2021-2-22 20:20:54
/**
* @file offb_node.cpp
* @brief Offboard control example node, written with MAVROS version 0.19.x, PX4 Pro Flight
* Stack and tested in Gazebo SITL
*/
#include <ros/ros.h>
#include <geometry_msgs/PoseStamped.h>
#include <mavros_msgs/CommandBool.h>
#include <mavros_msgs/SetMode.h>
#include <mavros_msgs/State.h>
mavros_msgs::State current_state;
void state_cb(const mavros_msgs::State::ConstPtr& msg){
current_state = *msg;
}
int main(int argc, char **argv)
{
ros::init(argc, argv, "offb_node");
ros::NodeHandle nh;
ros::Subscriber state_sub = nh.subscribe<mavros_msgs::State>
("mavros/state", 10, state_cb);
ros::Publisher local_pos_pub = nh.advertise<geometry_msgs::PoseStamped>
("mavros/setpoint_position/local", 10);
ros::ServiceClient arming_client = nh.serviceClient<mavros_msgs::CommandBool>
("mavros/cmd/arming");
ros::ServiceClient set_mode_client = nh.serviceClient<mavros_msgs::SetMode>
("mavros/set_mode");
//the setpoint publishing rate MUST be faster than 2Hz
ros::Rate rate(20.0);
// wait for FCU connection
while(ros::ok() && current_state.connected){
ros::spinOnce();
rate.sleep();
}
geometry_msgs::PoseStamped pose;
pose.pose.position.x = 0;
pose.pose.position.y = 0;
pose.pose.position.z = 2;
// //send a few setpoints before starting
// for(int i = 100; ros::ok() && i > 0; --i){
// local_pos_pub.publish(pose);
// ros::spinOnce();
// rate.sleep();
// }
mavros_msgs::SetMode offb_set_mode;
offb_set_mode.request.custom_mode = "OFFBOARD";
mavros_msgs::CommandBool arm_cmd;
arm_cmd.request.value = true;
ros::Time last_request = ros::Time::now();
while(ros::ok()){
if( current_state.mode != "OFFBOARD" && (ros::Time::now() - last_request > ros::Duration(5.0))){
if( set_mode_client.call(offb_set_mode) && offb_set_mode.response.mode_sent){
ROS_INFO("Offboard enabled");
}
last_request = ros::Time::now();
} else {
if( !current_state.armed && (ros::Time::now() - last_request > ros::Duration(5.0))){
if( arming_client.call(arm_cmd) && arm_cmd.response.success){
ROS_INFO("Vehicle armed");
}
last_request = ros::Time::now();
}
}
local_pos_pub.publish(pose);
ros::spinOnce();
rate.sleep();
}
return 0;
}
这个是官方示例的代码
发表于 2021-2-23 12:41:38
mavros/setpoint_position/cmd_vel,应该是mavros/setpoint_velocity/cmd_vel
我看了一下px4 rover,支持的还是84那个mavlink消息,支持发位置速度,好像还有姿态