ROS Resources: Documentation | Support | Discussion Forum | Index | Service Status | ros @ Robotics Stack Exchange
Ask Your Question

Revision history [back]

click to hide/show revision 1
initial version

I worked more than a year ago with MAVROS. please, be not so strict, if something wrong.

1) It is possible to control air MAVROS vehicle (PX4 stack) in offboard mode ONLY with position or altitude commands. I used the second one. Control altitude(roll, pitch, yaw) and throttle.

ros::Publisher mav_att_pub = nh.advertise<geometry_msgs::PoseStamped>( "mavros/setpoint_attitude/attitude", 100 );
ros::Publisher mav_thr_pub = nh.advertise<std_msgs::Float64>( "mavros/setpoint_attitude/att_throttle", 100 );

current vehicle orientation you may take here:

ros::Subscriber mav_imu_data_sub = nh.subscribe<sensor_msgs::Imu>( "mavros/imu/data", 100, mav_imu_data_callback );

send angles you may force the vehicle to change its position and orientation in XY plane. send throttle command from PID regulator with a distance or atm pressure sensor in the loop you may control altitude.

2) you MUST periodically send commands to the vehicle because there are PX4 save timer witch change control mode from offboard to stabilize.

3) use this one as starting point

4) use save channel with RC control with kill and change mode switchers for emergency situations

5) set stream rate ros::ServiceClient stream_rate_client = nh.serviceClient<mavros_msgs::streamrate>("mavros/set_stream_rate");

mavros_msgs::StreamRate streamRate;

streamRate.request.stream_id = 0;
streamRate.request.message_rate = 100;
streamRate.request.on_off = 1;

if (true == stream_rate_client.call(streamRate))
{
    ROS_INFO("OK. Stream rate set");
}
else
{
    ROS_INFO("Failed to call service: stream rate");
}

6) use high speed (921600) for serial MAVLINK port and rosrate 50 or higher for control commands

ros::Rate rate( 50.0 );

7) count ROS messages and set ros::Time::now()

I worked more than a year ago with MAVROS. please, be not so strict, if something wrong.

1) It is possible to control air MAVROS vehicle (PX4 stack) in offboard mode ONLY with position or altitude commands. I used the second one. Control altitude(roll, pitch, yaw) and throttle.

ros::Publisher mav_att_pub = nh.advertise<geometry_msgs::PoseStamped>( "mavros/setpoint_attitude/attitude", 100 );
ros::Publisher mav_thr_pub = nh.advertise<std_msgs::Float64>( "mavros/setpoint_attitude/att_throttle", 100 );

current vehicle orientation you may take here:

ros::Subscriber mav_imu_data_sub = nh.subscribe<sensor_msgs::Imu>( "mavros/imu/data", 100, mav_imu_data_callback );

send angles you may force the vehicle to change its position and orientation in XY plane. send throttle command from PID regulator with a distance or atm pressure sensor in the loop you may control altitude.

2) you MUST periodically send commands to the vehicle because there are PX4 save timer witch change control mode from offboard to stabilize.

3) use this one as starting point

4) use save channel with RC control with kill and change mode switchers for emergency situations

5) set stream rate ros::ServiceClient stream_rate_client = nh.serviceClient<mavros_msgs::streamrate>("mavros/set_stream_rate");

mavros_msgs::StreamRate streamRate;

streamRate.request.stream_id = 0;
streamRate.request.message_rate = 100;
streamRate.request.on_off = 1;

if (true == stream_rate_client.call(streamRate))
{
    ROS_INFO("OK. Stream rate set");
}
else
{
    ROS_INFO("Failed to call service: stream rate");
}

6) use high speed (921600) for serial MAVLINK port and rosrate 50 or higher for control commands

ros::Rate rate( 50.0 );

7) count ROS messages and set ros::Time::now()

full attitude and throttle msgs

// --------------------------------------
// PUB
// --------------------------------------
ros::Publisher mav_att_pub = nh.advertise<geometry_msgs::PoseStamped>( "mavros/setpoint_attitude/attitude", 100 );
ros::Publisher mav_thr_pub = nh.advertise<std_msgs::Float64>( "mavros/setpoint_attitude/att_throttle", 100 );

// attitude
geometry_msgs::PoseStamped cmd_att;
//throttle
std_msgs::Float64 cmd_thr;

// Create attitude command message
cmd_att.header.stamp = ros::Time::now();
cmd_att.header.seq = count;
cmd_att.pose.position.x = 0.0;
cmd_att.pose.position.y = 0.0;
cmd_att.pose.position.z = 0.0;

// here your desired angles
tf::Quaternion mav_orientation = tf::createQuaternionFromRPY( roll, pitch, yaw );

cmd_att.pose.orientation.x = mav_orientation.x();
cmd_att.pose.orientation.y = mav_orientation.y();
cmd_att.pose.orientation.z = mav_orientation.z();
cmd_att.pose.orientation.w = mav_orientation.w();

mav_att_pub.publish( cmd_att );

// here your throttle value a [0,1]
cmd_thr.data = a;

mav_thr_pub.publish( cmd_thr );

++count;

I worked more than a year ago with MAVROS. please, be not so strict, if something wrong.

1) It is possible to control air MAVROS vehicle (PX4 stack) in offboard mode ONLY with position or altitude attitude commands. I used the second one. Control altitude(roll, attitude(roll, pitch, yaw) and throttle.

ros::Publisher mav_att_pub = nh.advertise<geometry_msgs::PoseStamped>( "mavros/setpoint_attitude/attitude", 100 );
ros::Publisher mav_thr_pub = nh.advertise<std_msgs::Float64>( "mavros/setpoint_attitude/att_throttle", 100 );

current vehicle orientation you may take here:

ros::Subscriber mav_imu_data_sub = nh.subscribe<sensor_msgs::Imu>( "mavros/imu/data", 100, mav_imu_data_callback );

send angles you may force the vehicle to change its position and orientation in XY plane. send throttle command from PID regulator with a distance or atm pressure sensor in the loop you may control altitude.

2) you MUST periodically send commands to the vehicle because there are PX4 save timer witch change control mode from offboard to stabilize.

3) use this one as starting point

4) use save channel with RC control with kill and change mode switchers for emergency situations

5) set stream rate ros::ServiceClient stream_rate_client = nh.serviceClient<mavros_msgs::streamrate>("mavros/set_stream_rate");

mavros_msgs::StreamRate streamRate;

streamRate.request.stream_id = 0;
streamRate.request.message_rate = 100;
streamRate.request.on_off = 1;

if (true == stream_rate_client.call(streamRate))
{
    ROS_INFO("OK. Stream rate set");
}
else
{
    ROS_INFO("Failed to call service: stream rate");
}

6) use high speed (921600) for serial MAVLINK port and rosrate 50 or higher for control commands

ros::Rate rate( 50.0 );

7) count ROS messages and set ros::Time::now()

full attitude and throttle msgs

// --------------------------------------
// PUB
// --------------------------------------
ros::Publisher mav_att_pub = nh.advertise<geometry_msgs::PoseStamped>( "mavros/setpoint_attitude/attitude", 100 );
ros::Publisher mav_thr_pub = nh.advertise<std_msgs::Float64>( "mavros/setpoint_attitude/att_throttle", 100 );

// attitude
geometry_msgs::PoseStamped cmd_att;
//throttle
std_msgs::Float64 cmd_thr;

// Create attitude command message
cmd_att.header.stamp = ros::Time::now();
cmd_att.header.seq = count;
cmd_att.pose.position.x = 0.0;
cmd_att.pose.position.y = 0.0;
cmd_att.pose.position.z = 0.0;

// here your desired angles
tf::Quaternion mav_orientation = tf::createQuaternionFromRPY( roll, pitch, yaw );

cmd_att.pose.orientation.x = mav_orientation.x();
cmd_att.pose.orientation.y = mav_orientation.y();
cmd_att.pose.orientation.z = mav_orientation.z();
cmd_att.pose.orientation.w = mav_orientation.w();

mav_att_pub.publish( cmd_att );

// here your throttle value a [0,1]
cmd_thr.data = a;

mav_thr_pub.publish( cmd_thr );

++count;