Build error when creating custom mavros/mavlink messages. Melodic

asked 2020-02-27 08:55:02 -0500

Reghard_Grobler gravatar image

Hi, im currently trying to build my workspace on a Nvidea Jetson nano running ROS Melodic. I am trying to create a custom mavros message that I intend to use for passing data to px4 autopilot. I have followed the instructions here https://dev.px4.io/master/en/ros/mavros_custom_messages.html on px4 dev guide up until step 4. The remaining steps have already been completed on my PC running PX4. When building my workspace I get the following error:

Errors     << mavros_extras:make /home/honeybee/catkin_ws/logs/mavros_extras/build.make.000.log
/home/honeybee/catkin_ws/src/mavros/mavros_extras/src/plugins/marker_info.cpp: In member function ‘void 
mavros::extra_plugins::markerInfoPlugin::markerInfo_cb(const ConstPtr&)’:
/home/honeybee/catkin_ws/src/mavros/mavros_extras/src/plugins/marker_info.cpp:36:24: error: 
‘MARKER_INFO’ is not a member of ‘mavlink::common::msg’
mavlink::common::msg::MARKER_INFO mi = {};
                    ^~~~~~~~~~~

In /Workspace/src/Mavlink/message_definitions/V1.0/common.xml I have added the following lines to define my mavlink message:

    <message id="228" name="MARKER_INFO">
       <description>Information about the landing marker.</description>
       <field type="float" name="x_rel"> </field>
       <field type="float" name="y_rel"> </field>
       <field type="float" name="z_rel"> </field>
       <field type="uint8_t" name="spotted"> </field>
    </message>

Inside /workspace/src/mavros/mavros_extras/src/plugins/ I have created a cpp plugin called marker_info.cpp by following the px4 dev guide. Here is the code I used for this:

#include <mavros/mavros_plugin.h>
#include <pluginlib/class_list_macros.h>
#include <iostream>
#include <std_msgs/Char.h>
#include <std_msgs/Int32.h>
#include <geometry_msgs/Point.h>
#include <mavros_msgs/MarkerTarget.h>

namespace mavros {
namespace extra_plugins{

class markerInfoPlugin : public plugin::PluginBase {public:markerInfoPlugin() : PluginBase(),nh("~marker_Info")
{ };

 void initialize(UAS &uas_)
 {
     PluginBase::initialize(uas_);
     marker_info_sub = nh.subscribe("marker_info_sub", 10, &markerInfoPlugin::markerInfo_cb, this);
 };

 Subscriptions get_subscriptions()
 {
     return {/* RX disabled */ };
 }

 private:
 ros::NodeHandle nh;
 ros::Subscriber marker_info_sub;

void markerInfo_cb(const mavros_msgs::MarkerTarget::ConstPtr &req)
 {
  mavlink::common::msg::MARKER_INFO mi = {};
  mi.x_rel = req->marker_position.x;
  mi.y_rel = req->marker_position.y;
  mi.z_rel = req->marker_position.z;
  mi.spotted = req->marker_spotted;

      std::cout << "Got x Pos : " << req->marker_position.x <<  std::endl;
      std::cout << "Got y Pos : " << req->marker_position.y <<  std::endl;
      std::cout << "Got z Pos : " << req->marker_position.z <<  std::endl;
     std::cout << "Got marker_spotted : " << req->marker_spotted <<  std::endl;

      UAS_FCU(m_uas)->send_message_ignore_drop(mi);
 }
 };
 }   // namespace extra_plugins
 }   // namespace mavros

 PLUGINLIB_EXPORT_CLASS(mavros::extra_plugins::markerInfoPlugin, mavros::plugin::PluginBase)

From the error im receiving it seems that the plugin cannot find the message created in common.xml or perhaps it is not being created at all. I had this whole setup working on a PC running ROS kinetic in a SITL but now I want to get this working on the Nvidea Jetson nano. On the PC it was very straight forward, I had no issues building. But now I cant figure out what Im missing.

Here is the link to the mavlink repo I am trying to build https://github.com/mavlink/mavlink.git

Here is the link to the mavros repo I am tring to build https://github.com/mavlink/mavros.git

edit retag flag offensive close merge delete