Hi
We have are receiving a mavlink message SCALED_PRESSURE3 in our autopilot and we want to have a call back for it every time we receive it.
We created this plugin to publish a topic everytime we receive that message:
#include <mavros/mavros_plugin.h>
#include <bev_uav_msgs/Ambient.h>
namespace mavros {
namespace extra_plugins {
class ScaledPressure3Plugin : public plugin::PluginBase {
public:
ScaledPressure3Plugin() : PluginBase(),
cc_nh("~ScaledPressure3")
{ }
void initialize(UAS &uas_) {
PluginBase::initialize(uas_);
pubScaledPressure3 = cc_nh.advertise<bev_uav_msgs::Ambient>("sensing", 32, true);
}
Subscriptions get_subscriptions() {
return {
make_handler(&ScaledPressure3Plugin::handle_command),
};
}
private:
ros::NodeHandle cc_nh;
ros::Publisher pubScaledPressure3;
void handle_command(const mavlink::mavlink_message_t *, mavlink::common::msg::SCALED_PRESSURE3& msg)
{
ROS_INFO_STREAM("External sensor published");
auto ambient_msg = boost::make_shared<bev_uav_msgs::Ambient>();
ambient_msg->header.stamp = ros::Time::now();
ambient_msg->header.frame_id = "External Barometer";
ambient_msg->temperature = msg.temperature;
ambient_msg->pressure_type = 0; // Absolute
ambient_msg->pressure = msg.press_abs;
pubScaledPressure3.publish(ambient_msg);
}
};
} // namespace std_plugins
} // namespace mavros
#include <pluginlib/class_list_macros.h>
PLUGINLIB_EXPORT_CLASS(mavros::extra_plugins::ScaledPressure3Plugin, mavros::plugin::PluginBase)
We have addded this to our CMakelists and .xml file.
When we launch ros we see the plugin being loaded and initialized. In QGC we have the SCALED_PRESSURE3 at 2hz but the callback is never called.
Any ideas that might help why we can’t callback this message?
Thanks.