22 #include <mavros_msgs/HilControls.h> 23 #include <mavros_msgs/HilActuatorControls.h> 24 #include <mavros_msgs/HilStateQuaternion.h> 25 #include <mavros_msgs/HilGPS.h> 26 #include <mavros_msgs/HilSensor.h> 27 #include <mavros_msgs/OpticalFlowRad.h> 28 #include <mavros_msgs/RCIn.h> 31 namespace std_plugins {
42 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
50 PluginBase::initialize(uas_);
86 void handle_hil_controls(
const mavlink::mavlink_message_t *msg, mavlink::common::msg::HIL_CONTROLS &hil_controls) {
87 auto hil_controls_msg = boost::make_shared<mavros_msgs::HilControls>();
96 hil_controls_msg->roll_ailerons = hil_controls.roll_ailerons;
97 hil_controls_msg->pitch_elevator = hil_controls.pitch_elevator;
98 hil_controls_msg->yaw_rudder = hil_controls.yaw_rudder;
99 hil_controls_msg->throttle = hil_controls.throttle;
100 hil_controls_msg->aux1 = hil_controls.aux1;
101 hil_controls_msg->aux2 = hil_controls.aux2;
102 hil_controls_msg->aux3 = hil_controls.aux3;
103 hil_controls_msg->aux4 = hil_controls.aux4;
104 hil_controls_msg->mode = hil_controls.mode;
105 hil_controls_msg->nav_mode = hil_controls.nav_mode;
108 hil_controls_pub.
publish(hil_controls_msg);
112 auto hil_actuator_controls_msg = boost::make_shared<mavros_msgs::HilActuatorControls>();
115 const auto &arr = hil_actuator_controls.controls;
116 std::copy(arr.cbegin(), arr.cend(), hil_actuator_controls_msg->controls.begin());
117 hil_actuator_controls_msg->mode = hil_actuator_controls.mode;
118 hil_actuator_controls_msg->flags = hil_actuator_controls.flags;
120 hil_actuator_controls_pub.
publish(hil_actuator_controls_msg);
130 mavlink::common::msg::HIL_STATE_QUATERNION state_quat = {};
132 state_quat.time_usec = req->header.stamp.toNSec() / 1000;
137 state_quat.lat = req->geo.latitude * 1E7;
138 state_quat.lon = req->geo.longitude * 1E7;
142 state_quat.alt = req->geo.altitude * 1E3;
143 state_quat.ind_airspeed = req->ind_airspeed * 1E2;
144 state_quat.true_airspeed = req->true_airspeed * 1E2;
149 auto lin_vel = ftf::transform_frame_enu_ned<Eigen::Vector3d>(
163 state_quat.rollspeed = ang_vel.x();
164 state_quat.pitchspeed = ang_vel.y();
165 state_quat.yawspeed = ang_vel.z();
166 state_quat.vx = lin_vel.x();
167 state_quat.vy = lin_vel.y();
168 state_quat.vz = lin_vel.z();
169 state_quat.xacc = lin_acc.x();
170 state_quat.yacc = lin_acc.y();
171 state_quat.zacc = lin_acc.z();
182 mavlink::common::msg::HIL_GPS gps = {};
184 gps.time_usec = req->header.stamp.toNSec() / 1000;
185 gps.fix_type = req->fix_type;
186 gps.lat = req->geo.latitude * 1E7;
187 gps.lon = req->geo.longitude * 1E7;
191 gps.alt = req->geo.altitude * 1E3;
197 gps.eph = req->eph * 1E2;
198 gps.epv = req->epv * 1E2;
199 gps.vel = req->vel * 1E2;
200 gps.vn = req->vn * 1E2;
201 gps.ve = req->ve * 1E2;
202 gps.vd = req->vd * 1E2;
203 gps.cog = req->cog * 1E2;
205 gps.satellites_visible = req->satellites_visible;
215 mavlink::common::msg::HIL_SENSOR sensor = {};
217 sensor.time_usec = req->header.stamp.toNSec() / 1000;
223 auto mag = ftf::transform_frame_baselink_aircraft<Eigen::Vector3d>(
237 sensor.xacc = acc.x();
238 sensor.yacc = acc.y();
239 sensor.zacc = acc.z();
240 sensor.xgyro = gyro.x();
241 sensor.ygyro = gyro.y();
242 sensor.zgyro = gyro.z();
243 sensor.xmag = mag.x();
244 sensor.ymag = mag.y();
245 sensor.zmag = mag.z();
248 sensor.pressure_alt = req->pressure_alt;
249 sensor.temperature = req->temperature;
250 sensor.fields_updated = req->fields_updated;
261 mavlink::common::msg::HIL_OPTICAL_FLOW of = {};
270 req->integrated_xgyro,
271 req->integrated_ygyro,
272 req->integrated_zgyro));
274 of.time_usec = req->header.stamp.toNSec() / 1000;
275 of.sensor_id = INT8_MAX;
276 of.integration_time_us = req->integration_time_us;
285 of.integrated_x = int_xy.x();
286 of.integrated_y = int_xy.y();
287 of.integrated_xgyro = int_gyro.x();
288 of.integrated_ygyro = int_gyro.y();
289 of.integrated_zgyro = int_gyro.z();
290 of.time_delta_distance_us = req->time_delta_distance_us;
291 of.distance = req->distance;
292 of.quality = req->quality;
294 of.temperature = req->temperature * 100.0f;
304 mavlink::common::msg::HIL_RC_INPUTS_RAW rcin {};
306 constexpr
size_t MAX_CHANCNT = 12;
308 std::array<uint16_t, MAX_CHANCNT> channels;
309 auto n = std::min(req->channels.size(), channels.size());
310 std::copy(req->channels.begin(), req->channels.begin() +
n, channels.begin());
311 std::fill(channels.begin() +
n, channels.end(), UINT16_MAX);
313 rcin.time_usec = req->header.stamp.toNSec() / 100000;
318 rcin.chan1_raw = channels[ 0];
319 rcin.chan2_raw = channels[ 1];
320 rcin.chan3_raw = channels[ 2];
321 rcin.chan4_raw = channels[ 3];
322 rcin.chan5_raw = channels[ 4];
323 rcin.chan6_raw = channels[ 5];
324 rcin.chan7_raw = channels[ 6];
325 rcin.chan8_raw = channels[ 7];
326 rcin.chan9_raw = channels[ 8];
327 rcin.chan10_raw = channels[ 9];
328 rcin.chan11_raw = channels[10];
329 rcin.chan12_raw = channels[11];
static constexpr double TESLA_TO_GAUSS
Tesla to Gauss coeff.
MAVROS Plugin base class.
std::shared_ptr< MAVConnInterface const > ConstPtr
void publish(const boost::shared_ptr< M > &message) const
void handle_hil_controls(const mavlink::mavlink_message_t *msg, mavlink::common::msg::HIL_CONTROLS &hil_controls)
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))
ros::Subscriber hil_flow_sub
void quaternion_to_mavlink(const Eigen::Quaternion< _Scalar > &q, std::array< float, 4 > &qmsg)
Store Quaternion to MAVLink float[4] format.
EIGEN_MAKE_ALIGNED_OPERATOR_NEW HilPlugin()
ros::Publisher hil_controls_pub
T transform_orientation_enu_ned(const T &in)
Transform from attitude represented WRT ENU frame to attitude represented WRT NED frame...
ros::Subscriber hil_sensor_sub
ros::Publisher hil_actuator_controls_pub
PluginBase()
Plugin constructor Should not do anything before initialize()
T transform_frame_aircraft_baselink(const T &in)
Transform data expressed in Aircraft frame to Baselink frame.
Eigen::Quaterniond enu_orientation
void state_quat_cb(const mavros_msgs::HilStateQuaternion::ConstPtr &req)
Send hil_state_quaternion to FCU. Message specification: https://mavlink.io/en/messages/common.html#HIL_STATE_QUATERNION.
void optical_flow_cb(const mavros_msgs::OpticalFlowRad::ConstPtr &req)
Send simulated optical flow to FCU. Message specification: https://mavlink.io/en/messages/common.html#HIL_OPTICAL_FLOW.
void initialize(UAS &uas_) override
Plugin initializer.
ros::Subscriber hil_gps_sub
#define UAS_FCU(uasobjptr)
helper accessor to FCU link interface
ros::Time synchronise_stamp(uint32_t time_boot_ms)
Compute FCU message time from time_boot_ms or time_usec field.
Eigen::Vector3d to_eigen(const geometry_msgs::Point r)
Helper to convert common ROS geometry_msgs::Point to Eigen::Vector3d.
T transform_frame_baselink_aircraft(const T &in)
Transform data expressed in Baselink frame to Aircraft frame.
void sensor_cb(const mavros_msgs::HilSensor::ConstPtr &req)
Send hil_sensor to FCU. Message specification: https://mavlink.io/en/messages/common.html#HIL_SENSOR.
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
static constexpr double PASCAL_TO_MILLIBAR
Pascal to millBar coeff.
T transform_frame_enu_ned(const T &in)
Transform data expressed in ENU to NED frame.
void handle_hil_actuator_controls(const mavlink::mavlink_message_t *msg, mavlink::common::msg::HIL_ACTUATOR_CONTROLS &hil_actuator_controls)
std::vector< HandlerInfo > Subscriptions
Subscriptions vector.
ros::Subscriber hil_state_quaternion_sub
T transform_orientation_baselink_aircraft(const T &in)
Transform from attitude represented WRT baselink frame to attitude represented WRT body frame...
ros::Subscriber hil_rcin_sub
#define PLUGINLIB_EXPORT_CLASS(class_type, base_class_type)
Subscriptions get_subscriptions() override
Return vector of MAVLink message subscriptions (handlers)
void rcin_raw_cb(const mavros_msgs::RCIn::ConstPtr &req)
Send simulated received RAW values of the RC channels to the FCU. Message specification: https://mavl...
void gps_cb(const mavros_msgs::HilGPS::ConstPtr &req)
Send hil_gps to FCU. Message specification: https://mavlink.io/en/messages/common.html#HIL_GPS.