19 #include <mavros_msgs/RCIn.h> 20 #include <mavros_msgs/RCOut.h> 21 #include <mavros_msgs/OverrideRCIn.h> 24 namespace std_plugins {
39 PluginBase::initialize(uas_);
74 if (has_rc_channels_msg)
79 size_t offset = port.port * 8;
80 if (raw_rc_in.size() < offset + 8)
81 raw_rc_in.resize(offset + 8);
88 raw_rc_in[offset + 0] = port.chan1_raw;
89 raw_rc_in[offset + 1] = port.chan2_raw;
90 raw_rc_in[offset + 2] = port.chan3_raw;
91 raw_rc_in[offset + 3] = port.chan4_raw;
92 raw_rc_in[offset + 4] = port.chan5_raw;
93 raw_rc_in[offset + 5] = port.chan6_raw;
94 raw_rc_in[offset + 6] = port.chan7_raw;
95 raw_rc_in[offset + 7] = port.chan8_raw;
98 auto rcin_msg = boost::make_shared<mavros_msgs::RCIn>();
101 rcin_msg->rssi = port.rssi;
107 void handle_rc_channels(
const mavlink::mavlink_message_t *msg, mavlink::common::msg::RC_CHANNELS &channels)
109 constexpr
size_t MAX_CHANCNT = 18;
113 has_rc_channels_msg =
true;
115 if (channels.chancount > MAX_CHANCNT) {
117 "FCU receives %u RC channels, but RC_CHANNELS can store %zu",
118 channels.chancount, MAX_CHANCNT);
120 channels.chancount = MAX_CHANCNT;
123 raw_rc_in.resize(channels.chancount);
126 switch (channels.chancount) {
131 case 18: raw_rc_in[17] = channels.chan18_raw;
132 case 17: raw_rc_in[16] = channels.chan17_raw;
133 case 16: raw_rc_in[15] = channels.chan16_raw;
134 case 15: raw_rc_in[14] = channels.chan15_raw;
135 case 14: raw_rc_in[13] = channels.chan14_raw;
136 case 13: raw_rc_in[12] = channels.chan13_raw;
137 case 12: raw_rc_in[11] = channels.chan12_raw;
138 case 11: raw_rc_in[10] = channels.chan11_raw;
139 case 10: raw_rc_in[ 9] = channels.chan10_raw;
140 case 9: raw_rc_in[ 8] = channels.chan9_raw;
141 case 8: raw_rc_in[ 7] = channels.chan8_raw;
142 case 7: raw_rc_in[ 6] = channels.chan7_raw;
143 case 6: raw_rc_in[ 5] = channels.chan6_raw;
144 case 5: raw_rc_in[ 4] = channels.chan5_raw;
145 case 4: raw_rc_in[ 3] = channels.chan4_raw;
146 case 3: raw_rc_in[ 2] = channels.chan3_raw;
147 case 2: raw_rc_in[ 1] = channels.chan2_raw;
148 case 1: raw_rc_in[ 0] = channels.chan1_raw;
153 auto rcin_msg = boost::make_shared<mavros_msgs::RCIn>();
156 rcin_msg->rssi = channels.rssi;
166 uint8_t num_channels;
175 size_t offset = port.port * num_channels;
176 if (raw_rc_out.size() < offset + num_channels)
177 raw_rc_out.resize(offset + num_channels);
183 raw_rc_out[offset + 0] = port.servo1_raw;
184 raw_rc_out[offset + 1] = port.servo2_raw;
185 raw_rc_out[offset + 2] = port.servo3_raw;
186 raw_rc_out[offset + 3] = port.servo4_raw;
187 raw_rc_out[offset + 4] = port.servo5_raw;
188 raw_rc_out[offset + 5] = port.servo6_raw;
189 raw_rc_out[offset + 6] = port.servo7_raw;
190 raw_rc_out[offset + 7] = port.servo8_raw;
197 raw_rc_out[offset + 8] = port.servo9_raw;
198 raw_rc_out[offset + 9] = port.servo10_raw;
199 raw_rc_out[offset + 10] = port.servo11_raw;
200 raw_rc_out[offset + 11] = port.servo12_raw;
201 raw_rc_out[offset + 12] = port.servo13_raw;
202 raw_rc_out[offset + 13] = port.servo14_raw;
203 raw_rc_out[offset + 14] = port.servo15_raw;
204 raw_rc_out[offset + 15] = port.servo16_raw;
208 auto rcout_msg = boost::make_shared<mavros_msgs::RCOut>();
211 uint64_t time_usec = port.time_usec;
226 has_rc_channels_msg =
false;
234 mavlink::common::msg::RC_CHANNELS_OVERRIDE ovr = {};
242 ovr.chan1_raw = req->channels[0];
243 ovr.chan2_raw = req->channels[1];
244 ovr.chan3_raw = req->channels[2];
245 ovr.chan4_raw = req->channels[3];
246 ovr.chan5_raw = req->channels[4];
247 ovr.chan6_raw = req->channels[5];
248 ovr.chan7_raw = req->channels[6];
249 ovr.chan8_raw = req->channels[7];
MAVROS Plugin base class.
std::shared_ptr< MAVConnInterface const > ConstPtr
#define ROS_WARN_THROTTLE_NAMED(rate, name,...)
#define ROS_INFO_COND_NAMED(cond, name,...)
std::vector< uint16_t > raw_rc_in
void initialize(UAS &uas_) override
Plugin initializer.
void publish(const boost::shared_ptr< M > &message) const
std::atomic< bool > has_rc_channels_msg
Subscriptions get_subscriptions() override
Return vector of MAVLink message subscriptions (handlers)
Subscriber subscribe(const std::string &topic, uint32_t queue_size, void(T::*fp)(M), T *obj, const TransportHints &transport_hints=TransportHints())
HandlerInfo make_handler(const mavlink::msgid_t id, void(_C::*fn)(const mavlink::mavlink_message_t *msg, const mavconn::Framing framing))
void connection_cb(bool connected) override
void override_cb(const mavros_msgs::OverrideRCIn::ConstPtr req)
void handle_rc_channels_raw(const mavlink::mavlink_message_t *msg, mavlink::common::msg::RC_CHANNELS_RAW &port)
void handle_rc_channels(const mavlink::mavlink_message_t *msg, mavlink::common::msg::RC_CHANNELS &channels)
PluginBase()
Plugin constructor Should not do anything before initialize()
uint8_t get_tgt_system()
Return communication target system.
void handle_servo_output_raw(const mavlink::mavlink_message_t *msg, mavlink::common::msg::SERVO_OUTPUT_RAW &port)
ros::Subscriber override_sub
#define UAS_FCU(uasobjptr)
helper accessor to FCU link interface
bool is_ardupilotmega()
Check that FCU is APM.
ros::Time synchronise_stamp(uint32_t time_boot_ms)
Compute FCU message time from time_boot_ms or time_usec field.
ros::Publisher rc_out_pub
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
std::lock_guard< std::mutex > lock_guard
void enable_connection_cb()
std::vector< HandlerInfo > Subscriptions
Subscriptions vector.
#define PLUGINLIB_EXPORT_CLASS(class_type, base_class_type)
std::vector< uint16_t > raw_rc_out
bool is_px4()
Check that FCU is PX4.
uint8_t get_tgt_component()
Return communication target component.
std::recursive_mutex mutex