Mavlink messages always ignored

I’m trying to control a rover using explicit setpoint_velocity messages sent over mavros. Specifically, I’m running APMrover2 under SITL on Ubuntu using ROS kinetic and the latest mavros 0.21. Looking into handling of MAVLINK_MSG_ID_SET_POSITION_TARGET_LOCAL_NED in GCS_Mavlink.cpp I observe that the messages always arrive with ignore flags (masks):

  • pos_ignore true
  • vel_ignore false
  • acc_ignore true
  • yaw_ignore true
  • yaw_rate_ignore false
    However, at the end of the MAVLINK_MSG_ID_SET_POSITION_TARGET_LOCAL_NED case this combination of flags is explicitly not handled. Which means the autopilot ignores all messages that I publish to /mavros/setpoint_velocity/cmd_vel or /mavros/setpoint_velocity/cmd_vel_unstamped.

Is this the desired behaviour? If so, how can I explicitly control the robot in guided mode?

Hi All,

Just wondering if there is any update on this?

Just posting what my Colleague Dmitry has found so far about this problem. If would be great if we can get some input from the ardurover team

Background:
We could not control a rover (running under SITL) in guided mode by publishing to cmd_velocity topic. There were no issues with controlling a Copter the same way. We upgraded Mavros to 0.21.2 without any improvement.

After some debugging, apparently, the failure to control the robot over ROS messages is a feature, a limitation of the current ardurover (or mavros) implementations:
In branch Rover-3.2 of ardupilot project (at release rc1), file GCS_Mavlink.cpp, near line 1054 (handling MAVLINK_MSG_ID_SET_POSITION_TARGET_LOCAL_NED) the ignore flags are always appear as: position - ignore, velocity - do not ignore, acceleration - ignore, yaw - ignore, yaw rate - do not ignore
this combination of flags is not handled (explicitly ignored) at the end of the MAVLINK_MSG_ID_SET_POSITION_TARGET_LOCAL_NED case (if-then-else at lines 1117-1129)
the combination of flags is hard-coded by mavros itself; see mavros/src/plugins/setpoint_velocity.cpp, line 75: type mask cannot be changed by the user.
the two call-backs in mavros/src/plugins/setpoint_velocity.cpp (lines 91 and below) that respond to Twist and TwistStamped messages use the provided hard-coded mask.
therefore, any Twist or TwistStamped message published over ROS topics would have the combination of flags that is ignored by autopilot.
We implemented a workaround. If the incoming mavlink message has zero yaw rate and non-zero velocity, interpret it as setting velocity. Otherwise, if it has zero velocity and non-zero yaw rate, interpret as yaw rate. Set the ignore flags accordingly.

diff --git a/APMrover2/GCS_Mavlink.cpp b/APMrover2/GCS_Mavlink.cpp
index 90df2f7…1c23eb0 100644
— a/APMrover2/GCS_Mavlink.cpp
+++ b/APMrover2/GCS_Mavlink.cpp
@@ -1,5 +1,6 @@
#include “Rover.h”
#include “version.h”
+#include

#include “GCS_Mavlink.h”

@@ -1040,6 +1041,7 @@ void GCS_MAVLINK_Rover::handleMessage(mavlink_message_t* msg)

         // exit if vehicle is not in Guided mode
         if (rover.control_mode != &rover.mode_guided) {
  •            std::cerr << "rover is not guided, break out" << std::endl;
               break;
           }
    

@@ -1048,6 +1050,7 @@ void GCS_MAVLINK_Rover::handleMessage(mavlink_message_t* msg)
packet.coordinate_frame != MAV_FRAME_LOCAL_OFFSET_NED &&
packet.coordinate_frame != MAV_FRAME_BODY_NED &&
packet.coordinate_frame != MAV_FRAME_BODY_OFFSET_NED) {

  •            std::cerr << "bad coordinate frame, break out" << std::endl;
               break;
           }
    

@@ -1056,6 +1059,11 @@ void GCS_MAVLINK_Rover::handleMessage(mavlink_message_t* msg)
bool acc_ignore = packet.type_mask & MAVLINK_SET_POS_TYPE_MASK_ACC_IGNORE;
bool yaw_ignore = packet.type_mask & MAVLINK_SET_POS_TYPE_MASK_YAW_IGNORE;
bool yaw_rate_ignore = packet.type_mask & MAVLINK_SET_POS_TYPE_MASK_YAW_RATE_IGNORE;

  •        // 1,0,1,1,0
    
  •        if ( !yaw_rate_ignore && !vel_ignore ) {
    
  •            if ( packet.yaw_rate == 0.0 && ( packet.vx != 0.0 || packet.vy != 0.0 ) ) { yaw_rate_ignore = true; }
    
  •            if ( packet.vx == 0.0 && packet.vy == 0.0 && packet.yaw_rate != 0.0 ) { vel_ignore = true; }
    
  •        }
    
           // prepare target position
           Location target_loc = rover.current_loc;
    

@@ -1126,6 +1134,8 @@ void GCS_MAVLINK_Rover::handleMessage(mavlink_message_t* msg)
} else if (pos_ignore && vel_ignore && acc_ignore && yaw_ignore && !yaw_rate_ignore) {
// consume just turn rate(probably only skid steering vehicles can do this)
rover.mode_guided.set_desired_turn_rate_and_speed(target_turn_rate_cds, 0.0f);

  •        } else {
    
  •            std::cerr << "unsupported combination of ignore flags" << std::endl;
           }
           break;
       }
    

With these changes in place, we can control the rover in SITL by publishing ros messages to cmd_vel and cmd_vel_unstamped topics.

However, this is a hack and presumably a proper solution would be implemented in ArduRover itself. Are we able to inclue these changes in the next RC release ?