Custom mavros message
Create custom mavros receiver and sender
time frame_stamp # Timestamp
float32 servo_setpoint
#include <mavros/mavros_plugin.h>
#include <mavros_msgs/GripperServo.h>
namespace mavros
{
namespace extra_plugins
{
class GripperServoPlugin : public plugin::PluginBase
{
public:
GripperServoPlugin() : PluginBase(),
status_nh("~gripper_servo")
{
}
void initialize(UAS &uas_)
{
PluginBase::initialize(uas_);
status_sub = status_nh.subscribe("gripper_servo", 10, &GripperServoPlugin::status_cb, this);
}
Subscriptions get_subscriptions()
{
return {/* Rx disabled */};
}
private:
ros::NodeHandle status_nh;
ros::Subscriber status_sub;
/**
* @param req received GripperServo msg
*/
void status_cb(const mavros_msgs::GripperServo::ConstPtr &req)
{
mavlink::common::msg::GRIPPER_SERVO gripper{};
gripper.servo_setpoint = req->servo_setpoint;
UAS_FCU(m_uas)->send_message_ignore_drop(gripper);
}
};
} // namespace extra_plugins
} // namespace mavros
#include <pluginlib/class_list_macros.h>
PLUGINLIB_EXPORT_CLASS(mavros::extra_plugins::GripperServoPlugin, mavros::plugin::PluginBase)Inside px4
Last updated
Was this helpful?