Send custom MAVLink message

Hi,

I want to send a custom uOrb message through mavlink.
I follow the guide: http://dev.px4.io/custom-mavlink-message.html.
The class that I added to mavlink_messages.cpp is this one:

class MavlinkStreamCaTrajectory : public MavlinkStream
{
public:
    const char *get_name() const
    {
        return MavlinkStreamCaTrajectory::get_name_static();
    }
    static const char *get_name_static()
    {
        return "CA_TRAJECTORY";
    }
    static uint8_t get_id_static()
    {
        return MAVLINK_MSG_ID_CA_TRAJECTORY;
    }
		uint8_t get_id()
		{
			return get_id_static();
		}
    static MavlinkStream *new_instance(Mavlink *mavlink)
    {
        return new MavlinkStreamCaTrajectory(mavlink);
    }
    unsigned get_size()
    {
        return MAVLINK_MSG_ID_CA_TRAJECTORY_LEN + MAVLINK_NUM_NON_PAYLOAD_BYTES;
    }

private:
    MavlinkOrbSubscription *_sub;
    uint64_t _ca_traj_time;

    /* do not allow top copying this class */
    MavlinkStreamCaTrajectory(MavlinkStreamCaTrajectory &);
    MavlinkStreamCaTrajectory& operator = (const MavlinkStreamCaTrajectory &);

protected:
    explicit MavlinkStreamCaTrajectory(Mavlink *mavlink) : MavlinkStream(mavlink),
        _sub(_mavlink->add_orb_subscription(ORB_ID(ca_trajectory))),  // make sure you enter the name of your uorb topic here
        _ca_traj_time(0)
    {}

    void send(const hrt_abstime t)
    {
      struct ca_traj_struct_s _ca_trajectory;    //make sure ca_traj_struct_s is the definition of your uorb topic

      if (_sub->update(&_ca_traj_time, &_ca_trajectory)) {
        mavlink_ca_trajectory_t _msg_ca_trajectory;  //make sure mavlink_ca_trajectory_t is the definition of your custom mavlink message

        _msg_ca_trajectory.timestamp = _ca_trajectory.timestamp;
        _msg_ca_trajectory.time_start_usec = _ca_trajectory.time_start_usec;
        _msg_ca_trajectory.time_stop_usec  = _ca_trajectory.time_stop_usec;
        _msg_ca_trajectory.coefficients =_ca_trajectory.coefficients;
        _msg_ca_trajectory.seq_id = _ca_trajectory.seq_id;
        mavlink_msg_ca_trajectory_send_struct(_mavlink->get_channel(), &_msg_ca_trajectory);
      }
    }
};

I appended the stream class

StreamListItem *streams_list[] = {
...
  new StreamListItem(&MavlinkStreamCaTrajectory::new_instance, &MavlinkStreamCaTrajectory::get_name_static,&MavlinkStreamCaTrajectory::get_id_static),nullptr
};

Differences respect to the guide:

  1. Since the constructor of class StreamListItem requires the id i added the method get_name_static to MavlinkStreamCaTrajectory class.
  2. In the send method of class MavlinkStreamCaTrajectory I changed the method
    _mavlink->send_message(MAVLINK_MSG_ID_CA_TRAJECTORY, &_msg_ca_trajectory);
    with:
    mavlink_msg_ca_trajectory_send_struct(_mavlink->get_channel(), &_msg_ca_trajectory);
    because I had a compile error.

Now I am able to compile the code but the function send is never used even if I send ca_trajectory uOrb message and I don’t recive any ca_trajectory mavlink message.

I think that something is missed but I don’t no what.

Solved. See https://github.com/PX4/Firmware/issues/5597

Hello, I saw the github page https://github.com/PX4/Firmware/issues/5597, but I still don’t know where to put the generated directory custom_messages in mavros package. And could you share your mavros code? Thanks a lot.

Are you using mavros 0.17 or 0.18?

Yes, I use mavros 0.17.

Now, I have extended the mavros, and enabled the mavlink stream in posix-configs/SITL/init/lpe/iris, but I still can’t receive my custom mavlink messages :cry:

Maybe my way to extend mavros is wrong, I can confirm the custom messages were sent by px4.
For extending mavros, I put the directory custom_messages that generated by pymavlink into the directory mavros/include, and added the include sentence in mavros.cpp.
Do I miss anything? Thanks a lot.

See this issue.

I want to know how you judge whether px4 has sent the custom messages? Now I’m not sure whether px4 has sent my custom messages.

I extended mavros and it worked. If you want to see the mavlink streaming, I think that the fast way is to use pymavlink or mavproxy.