From fa50eca9b2fba74fc330787fb9380df0607f90da Mon Sep 17 00:00:00 2001 From: Hancheol Choi Date: Thu, 7 Sep 2017 15:14:27 +0900 Subject: [PATCH] Update mavlink_messages.cpp In mavlink_messages.cpp: 4058, _attitude_sp_sub(_mavlink->add_orb_subscription(ORB_ID(fw_pos_ctrl_status))), -> _attitude_sp_sub(_mavlink->add_orb_subscription(ORB_ID(vehicle_attitude_setpoint))), Isn't it right? --- src/modules/mavlink/mavlink_messages.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/modules/mavlink/mavlink_messages.cpp b/src/modules/mavlink/mavlink_messages.cpp index 4378d0f83edd..7624e5e73321 100644 --- a/src/modules/mavlink/mavlink_messages.cpp +++ b/src/modules/mavlink/mavlink_messages.cpp @@ -4055,7 +4055,7 @@ class MavlinkStreamHighLatency : public MavlinkStream _actuator_time(0), _airspeed_sub(_mavlink->add_orb_subscription(ORB_ID(airspeed))), _airspeed_time(0), - _attitude_sp_sub(_mavlink->add_orb_subscription(ORB_ID(fw_pos_ctrl_status))), + _attitude_sp_sub(_mavlink->add_orb_subscription(ORB_ID(vehicle_attitude_setpoint))), _attitude_sp_time(0), _attitude_sub(_mavlink->add_orb_subscription(ORB_ID(vehicle_attitude))), _attitude_time(0),