Compile/Build Error : unable to build/compile px4 with a new custom MAVLINK msg broadcaster

About Myself
Hello Guys, Thanks for taking ur time to read this post to try to help me. please excuse my noobness if I ask any silly doubts. anyways back to the main topic

For a small Project of mine, I need pixhawk to interface with a custom sensor that I have made, log that data and send it back to QGC for live telemetry.

To accomplish this, I have already made a custom driver which interfaces with an Arduino through i2c and reads that data to be published onto a custom uorb topic (called pr01_data )

The data is being read and it is logged properly. for the next step of live telemetry, i am trying to create a custom mavlink msg and send it to qgc

for this, I followed the given guide mentioned at http://dev.px4.io/en/middleware/mavlink.html

What i have done
i created a custom mavlink msg and headers using the mavlink lib (Defining XML Enums/Messages · MAVLink Developer Guide)

then i tried broacasting it using pixhawk through the code snippet provided.i modified the code snippet example given for my use

My defn of MavlinkStream Class

 #include <uORB/topics/pr01_data.h>
#include <v2.0/px4stack/mavlink.h>
#include <v2.0/px4stack/mavlink_msg_pr01_data.h>

    class MavlinkStreamPR01 : public MavlinkStream
{
public:
    const char *get_name() const
    {
        return MavlinkStreamPR01::get_name_static();
    }
    static const char *get_name_static()
    {
        return "PR01_DATA";
    }
    uint16_t get_id_static()
    {
        return MAVLINK_MSG_ID_PR01_DATA;
    }
    uint16_t get_id()
    {
        return get_id_static();
    }
    static MavlinkStream *new_instance(Mavlink *mavlink)
    {
        return new MavlinkStreamPR01(mavlink);
    }

    unsigned get_size()
    {
        return MAVLINK_MSG_ID_PR01_DATA_LEN + MAVLINK_NUM_NON_PAYLOAD_BYTES;
    }

private:
    MavlinkOrbSubscription *_sub;
    uint64_t _pr01_time;

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

protected:
    explicit MavlinkStreamPR01(Mavlink *mavlink) : MavlinkStream(mavlink),
        _sub(_mavlink->add_orb_subscription(ORB_ID(pr01_data))),  // make sure you enter the name of your uORB topic here
        _pr01_time(0)
    {}

    bool send(const hrt_abstime t)
    {
        struct pr01_data_s _pr01;    //make sure ca_traj_struct_s is the definition of your uORB topic

        if (_sub->update(&_pr01_time, &_pr01)) {
            mavlink_pr01_data_t _msg_pr01;  //make sure mavlink_pr01_t is the definition of your custom MAVLink message

            _msg_pr01.timestamp = _pr01.timestamp;
            _msg_pr01.status = _pr01.status;
            _msg_pr01.thickness =_pr01.thickness;
            _msg_pr01.contact = _pr01.contact;

            mavlink_msg_pr01_data_send_struct(_mavlink->get_channel(), &_msg_pr01);
        }

        return true;
    }
};

My error

when i compile with only the class included i get no errors, but when i append the class to streams_list, I get errors

when i append it like mentioned in the example

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

to the end of mavlink_messages.cpp , i get an error during compile

error: conflicting declaration 'StreamListItem* streams_list'
 StreamListItem *streams_list = {

when i instead add it directly to the defn of streams_list declaration
i get an error

error: no matching function for call to 'StreamListItem::StreamListItem(MavlinkStream* (*)(Mavlink*), const char* (*)(), uint16_t (MavlinkStreamPR01::*)())'
  StreamListItem(&MavlinkStreamPR01::new_instance, &MavlinkStreamPR01::get_name_static, &MavlinkStreamPR01::get_id_static)

i tried searching the forums and also googled for any silly errors i might have made. any help is much appreciated, thanks in advance

Hi,

I think the example is outdated for adding new items to the streams_list. I figured this out by looking at how the other streams are added to the list.

I would recommend to just copy the last line and adjust it to your stream, this usually worked for me (just don’t forget to add the comma for previous last stream).

I hope it works that way.

@acfloria Can you do a PR to the docs? http://dev.px4.io/en/middleware/mavlink.html

@bkueng This has broken in the past. Is there any way we can have a real example in CI so that if things stop building we get notification? And if someone has a problem we can point to a working solution?

@acfloria Thanks for ur suggestion and ur time
when the example provided in the doc didn’t work, I also came to the same conclusion

I copied the last line and tried adding it to the stream_list array as follows ( Check the last line )

static const StreamListItem streams_list[] = {
	StreamListItem(&MavlinkStreamHeartbeat::new_instance, &MavlinkStreamHeartbeat::get_name_static, &MavlinkStreamHeartbeat::get_id_static),
	StreamListItem(&MavlinkStreamStatustext::new_instance, &MavlinkStreamStatustext::get_name_static, &MavlinkStreamStatustext::get_id_static),
	StreamListItem(&MavlinkStreamCommandLong::new_instance, &MavlinkStreamCommandLong::get_name_static, &MavlinkStreamCommandLong::get_id_static),
	StreamListItem(&MavlinkStreamSysStatus::new_instance, &MavlinkStreamSysStatus::get_name_static, &MavlinkStreamSysStatus::get_id_static),
	StreamListItem(&MavlinkStreamHighresIMU::new_instance, &MavlinkStreamHighresIMU::get_name_static, &MavlinkStreamHighresIMU::get_id_static),
	StreamListItem(&MavlinkStreamScaledIMU::new_instance, &MavlinkStreamScaledIMU::get_name_static, &MavlinkStreamScaledIMU::get_id_static),
	StreamListItem(&MavlinkStreamScaledIMU2::new_instance, &MavlinkStreamScaledIMU2::get_name_static, &MavlinkStreamScaledIMU2::get_id_static),
	StreamListItem(&MavlinkStreamScaledIMU3::new_instance, &MavlinkStreamScaledIMU3::get_name_static, &MavlinkStreamScaledIMU3::get_id_static),
	StreamListItem(&MavlinkStreamAttitude::new_instance, &MavlinkStreamAttitude::get_name_static, &MavlinkStreamAttitude::get_id_static),
	StreamListItem(&MavlinkStreamAttitudeQuaternion::new_instance, &MavlinkStreamAttitudeQuaternion::get_name_static, &MavlinkStreamAttitudeQuaternion::get_id_static),
	StreamListItem(&MavlinkStreamVFRHUD::new_instance, &MavlinkStreamVFRHUD::get_name_static, &MavlinkStreamVFRHUD::get_id_static),
	StreamListItem(&MavlinkStreamGPSRawInt::new_instance, &MavlinkStreamGPSRawInt::get_name_static, &MavlinkStreamGPSRawInt::get_id_static),
	StreamListItem(&MavlinkStreamGPS2Raw::new_instance, &MavlinkStreamGPS2Raw::get_name_static, &MavlinkStreamGPS2Raw::get_id_static),
	StreamListItem(&MavlinkStreamSystemTime::new_instance, &MavlinkStreamSystemTime::get_name_static, &MavlinkStreamSystemTime::get_id_static),
	StreamListItem(&MavlinkStreamTimesync::new_instance, &MavlinkStreamTimesync::get_name_static, &MavlinkStreamTimesync::get_id_static),
	StreamListItem(&MavlinkStreamGlobalPositionInt::new_instance, &MavlinkStreamGlobalPositionInt::get_name_static, &MavlinkStreamGlobalPositionInt::get_id_static),
	StreamListItem(&MavlinkStreamLocalPositionNED::new_instance, &MavlinkStreamLocalPositionNED::get_name_static, &MavlinkStreamLocalPositionNED::get_id_static),
	StreamListItem(&MavlinkStreamOdometry::new_instance, &MavlinkStreamOdometry::get_name_static, &MavlinkStreamOdometry::get_id_static),
	StreamListItem(&MavlinkStreamEstimatorStatus::new_instance, &MavlinkStreamEstimatorStatus::get_name_static, &MavlinkStreamEstimatorStatus::get_id_static),
	StreamListItem(&MavlinkStreamAttPosMocap::new_instance, &MavlinkStreamAttPosMocap::get_name_static, &MavlinkStreamAttPosMocap::get_id_static),
	StreamListItem(&MavlinkStreamHomePosition::new_instance, &MavlinkStreamHomePosition::get_name_static, &MavlinkStreamHomePosition::get_id_static),
	StreamListItem(&MavlinkStreamServoOutputRaw<0>::new_instance, &MavlinkStreamServoOutputRaw<0>::get_name_static, &MavlinkStreamServoOutputRaw<0>::get_id_static),
	StreamListItem(&MavlinkStreamServoOutputRaw<1>::new_instance, &MavlinkStreamServoOutputRaw<1>::get_name_static, &MavlinkStreamServoOutputRaw<1>::get_id_static),
	StreamListItem(&MavlinkStreamServoOutputRaw<2>::new_instance, &MavlinkStreamServoOutputRaw<2>::get_name_static, &MavlinkStreamServoOutputRaw<2>::get_id_static),
	StreamListItem(&MavlinkStreamServoOutputRaw<3>::new_instance, &MavlinkStreamServoOutputRaw<3>::get_name_static, &MavlinkStreamServoOutputRaw<3>::get_id_static),
	StreamListItem(&MavlinkStreamHILActuatorControls::new_instance, &MavlinkStreamHILActuatorControls::get_name_static, &MavlinkStreamHILActuatorControls::get_id_static),
	StreamListItem(&MavlinkStreamPositionTargetGlobalInt::new_instance, &MavlinkStreamPositionTargetGlobalInt::get_name_static, &MavlinkStreamPositionTargetGlobalInt::get_id_static),
	StreamListItem(&MavlinkStreamLocalPositionSetpoint::new_instance, &MavlinkStreamLocalPositionSetpoint::get_name_static, &MavlinkStreamLocalPositionSetpoint::get_id_static),
	StreamListItem(&MavlinkStreamAttitudeTarget::new_instance, &MavlinkStreamAttitudeTarget::get_name_static, &MavlinkStreamAttitudeTarget::get_id_static),
	StreamListItem(&MavlinkStreamRCChannels::new_instance, &MavlinkStreamRCChannels::get_name_static, &MavlinkStreamRCChannels::get_id_static),
	StreamListItem(&MavlinkStreamManualControl::new_instance, &MavlinkStreamManualControl::get_name_static, &MavlinkStreamManualControl::get_id_static),
	StreamListItem(&MavlinkStreamTrajectoryRepresentationWaypoints::new_instance, &MavlinkStreamTrajectoryRepresentationWaypoints::get_name_static, &MavlinkStreamTrajectoryRepresentationWaypoints::get_id_static),
	StreamListItem(&MavlinkStreamOpticalFlowRad::new_instance, &MavlinkStreamOpticalFlowRad::get_name_static, &MavlinkStreamOpticalFlowRad::get_id_static),
	StreamListItem(&MavlinkStreamActuatorControlTarget<0>::new_instance, &MavlinkStreamActuatorControlTarget<0>::get_name_static, &MavlinkStreamActuatorControlTarget<0>::get_id_static),
	StreamListItem(&MavlinkStreamActuatorControlTarget<1>::new_instance, &MavlinkStreamActuatorControlTarget<1>::get_name_static, &MavlinkStreamActuatorControlTarget<1>::get_id_static),
	StreamListItem(&MavlinkStreamActuatorControlTarget<2>::new_instance, &MavlinkStreamActuatorControlTarget<2>::get_name_static, &MavlinkStreamActuatorControlTarget<2>::get_id_static),
	StreamListItem(&MavlinkStreamActuatorControlTarget<3>::new_instance, &MavlinkStreamActuatorControlTarget<3>::get_name_static, &MavlinkStreamActuatorControlTarget<3>::get_id_static),
	StreamListItem(&MavlinkStreamNamedValueFloat::new_instance, &MavlinkStreamNamedValueFloat::get_name_static, &MavlinkStreamNamedValueFloat::get_id_static),
	StreamListItem(&MavlinkStreamDebug::new_instance, &MavlinkStreamDebug::get_name_static, &MavlinkStreamDebug::get_id_static),
	StreamListItem(&MavlinkStreamDebugVect::new_instance, &MavlinkStreamDebugVect::get_name_static, &MavlinkStreamDebugVect::get_id_static),
	StreamListItem(&MavlinkStreamDebugFloatArray::new_instance, &MavlinkStreamDebugFloatArray::get_name_static, &MavlinkStreamDebugFloatArray::get_id_static),
	StreamListItem(&MavlinkStreamNavControllerOutput::new_instance, &MavlinkStreamNavControllerOutput::get_name_static, &MavlinkStreamNavControllerOutput::get_id_static),
	StreamListItem(&MavlinkStreamCameraCapture::new_instance, &MavlinkStreamCameraCapture::get_name_static, &MavlinkStreamCameraCapture::get_id_static),
	StreamListItem(&MavlinkStreamCameraTrigger::new_instance, &MavlinkStreamCameraTrigger::get_name_static, &MavlinkStreamCameraTrigger::get_id_static),
	StreamListItem(&MavlinkStreamCameraImageCaptured::new_instance, &MavlinkStreamCameraImageCaptured::get_name_static, &MavlinkStreamCameraImageCaptured::get_id_static),
	StreamListItem(&MavlinkStreamDistanceSensor::new_instance, &MavlinkStreamDistanceSensor::get_name_static, &MavlinkStreamDistanceSensor::get_id_static),
	StreamListItem(&MavlinkStreamExtendedSysState::new_instance, &MavlinkStreamExtendedSysState::get_name_static, &MavlinkStreamExtendedSysState::get_id_static),
	StreamListItem(&MavlinkStreamAltitude::new_instance, &MavlinkStreamAltitude::get_name_static, &MavlinkStreamAltitude::get_id_static),
	StreamListItem(&MavlinkStreamADSBVehicle::new_instance, &MavlinkStreamADSBVehicle::get_name_static, &MavlinkStreamADSBVehicle::get_id_static),
	StreamListItem(&MavlinkStreamUTMGlobalPosition::new_instance, &MavlinkStreamUTMGlobalPosition::get_name_static, &MavlinkStreamUTMGlobalPosition::get_id_static),
	StreamListItem(&MavlinkStreamCollision::new_instance, &MavlinkStreamCollision::get_name_static, &MavlinkStreamCollision::get_id_static),
	StreamListItem(&MavlinkStreamWind::new_instance, &MavlinkStreamWind::get_name_static, &MavlinkStreamWind::get_id_static),
	StreamListItem(&MavlinkStreamMountOrientation::new_instance, &MavlinkStreamMountOrientation::get_name_static, &MavlinkStreamMountOrientation::get_id_static),
	StreamListItem(&MavlinkStreamHighLatency2::new_instance, &MavlinkStreamHighLatency2::get_name_static, &MavlinkStreamHighLatency2::get_id_static),
	StreamListItem(&MavlinkStreamGroundTruth::new_instance, &MavlinkStreamGroundTruth::get_name_static, &MavlinkStreamGroundTruth::get_id_static),
	StreamListItem(&MavlinkStreamPing::new_instance, &MavlinkStreamPing::get_name_static, &MavlinkStreamPing::get_id_static),
	StreamListItem(&MavlinkStreamOrbitStatus::new_instance, &MavlinkStreamOrbitStatus::get_name_static, &MavlinkStreamOrbitStatus::get_id_static),
       StreamListItem(&MavlinkStreamPR01::new_instance, &MavlinkStreamPR01::get_name_static, &MavlinkStreamPR01::get_id_static)
};

when i do this i get the error

error: no matching function for call to 'StreamListItem::StreamListItem(MavlinkStream* (*)(Mavlink*), const char* (*)(), uint16_t (MavlinkStreamPR01::*)())'
  StreamListItem(&MavlinkStreamPR01::new_instance, &MavlinkStreamPR01::get_name_static, &MavlinkStreamPR01::get_id_static)

from what i understand , this error ,the compiler is trying to say it isnt able to find a fuction prototype/defn (the streamlistitem constructor) with the given signature (the one mentioned in the error and typed out in the array)

please correct me if i am wrong

The real example would just be an existing stream. I think the best we can do is to point to existing code, instead of copying it into the docs. Then it’s up-to-date for sure.

You are missing the static for the uint16_t get_id_static() declaration.

1 Like

shit!!!, it was such a stupid mistake
it is working right now.
Thanks a lot guys
the official doc doesn’t contain the static keyword, please update it so others don’t fumble as I did