|
|
|
@ -88,9 +88,9 @@ static const float mg2ms2 = CONSTANTS_ONE_G / 1000.0f;
@@ -88,9 +88,9 @@ static const float mg2ms2 = CONSTANTS_ONE_G / 1000.0f;
|
|
|
|
|
|
|
|
|
|
MavlinkReceiver::MavlinkReceiver(Mavlink *parent) : |
|
|
|
|
_mavlink(parent), |
|
|
|
|
status {}, |
|
|
|
|
hil_local_pos {}, |
|
|
|
|
_control_mode {}, |
|
|
|
|
status{}, |
|
|
|
|
hil_local_pos{}, |
|
|
|
|
_control_mode{}, |
|
|
|
|
_global_pos_pub(-1), |
|
|
|
|
_local_pos_pub(-1), |
|
|
|
|
_attitude_pub(-1), |
|
|
|
@ -121,9 +121,7 @@ MavlinkReceiver::MavlinkReceiver(Mavlink *parent) :
@@ -121,9 +121,7 @@ MavlinkReceiver::MavlinkReceiver(Mavlink *parent) :
|
|
|
|
|
_old_timestamp(0), |
|
|
|
|
_hil_local_proj_inited(0), |
|
|
|
|
_hil_local_alt0(0.0f), |
|
|
|
|
_hil_local_proj_ref {}, |
|
|
|
|
_time_offset_avg_alpha(0.75), |
|
|
|
|
_time_offset(0) |
|
|
|
|
_hil_local_proj_ref{} |
|
|
|
|
{ |
|
|
|
|
|
|
|
|
|
// make sure the FTP server is started
|
|
|
|
@ -277,35 +275,22 @@ MavlinkReceiver::handle_message_command_long(mavlink_message_t *msg)
@@ -277,35 +275,22 @@ MavlinkReceiver::handle_message_command_long(mavlink_message_t *msg)
|
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
struct vehicle_command_s vcmd; |
|
|
|
|
|
|
|
|
|
memset(&vcmd, 0, sizeof(vcmd)); |
|
|
|
|
|
|
|
|
|
/* Copy the content of mavlink_command_long_t cmd_mavlink into command_t cmd */ |
|
|
|
|
vcmd.param1 = cmd_mavlink.param1; |
|
|
|
|
|
|
|
|
|
vcmd.param2 = cmd_mavlink.param2; |
|
|
|
|
|
|
|
|
|
vcmd.param3 = cmd_mavlink.param3; |
|
|
|
|
|
|
|
|
|
vcmd.param4 = cmd_mavlink.param4; |
|
|
|
|
|
|
|
|
|
vcmd.param5 = cmd_mavlink.param5; |
|
|
|
|
|
|
|
|
|
vcmd.param6 = cmd_mavlink.param6; |
|
|
|
|
|
|
|
|
|
vcmd.param7 = cmd_mavlink.param7; |
|
|
|
|
|
|
|
|
|
// XXX do proper translation
|
|
|
|
|
vcmd.command = (enum VEHICLE_CMD)cmd_mavlink.command; |
|
|
|
|
|
|
|
|
|
vcmd.target_system = cmd_mavlink.target_system; |
|
|
|
|
|
|
|
|
|
vcmd.target_component = cmd_mavlink.target_component; |
|
|
|
|
|
|
|
|
|
vcmd.source_system = msg->sysid; |
|
|
|
|
|
|
|
|
|
vcmd.source_component = msg->compid; |
|
|
|
|
|
|
|
|
|
vcmd.confirmation = cmd_mavlink.confirmation; |
|
|
|
|
|
|
|
|
|
if (_cmd_pub < 0) { |
|
|
|
@ -346,34 +331,22 @@ MavlinkReceiver::handle_message_command_int(mavlink_message_t *msg)
@@ -346,34 +331,22 @@ MavlinkReceiver::handle_message_command_int(mavlink_message_t *msg)
|
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
struct vehicle_command_s vcmd; |
|
|
|
|
|
|
|
|
|
memset(&vcmd, 0, sizeof(vcmd)); |
|
|
|
|
|
|
|
|
|
/* Copy the content of mavlink_command_int_t cmd_mavlink into command_t cmd */ |
|
|
|
|
vcmd.param1 = cmd_mavlink.param1; |
|
|
|
|
|
|
|
|
|
vcmd.param2 = cmd_mavlink.param2; |
|
|
|
|
|
|
|
|
|
vcmd.param3 = cmd_mavlink.param3; |
|
|
|
|
|
|
|
|
|
vcmd.param4 = cmd_mavlink.param4; |
|
|
|
|
|
|
|
|
|
/* these are coordinates as 1e7 scaled integers to work around the 32 bit floating point limits */ |
|
|
|
|
vcmd.param5 = ((double)cmd_mavlink.x) / 1e7; |
|
|
|
|
|
|
|
|
|
vcmd.param6 = ((double)cmd_mavlink.y) / 1e7; |
|
|
|
|
|
|
|
|
|
vcmd.param7 = cmd_mavlink.z; |
|
|
|
|
|
|
|
|
|
// XXX do proper translation
|
|
|
|
|
vcmd.command = (enum VEHICLE_CMD)cmd_mavlink.command; |
|
|
|
|
|
|
|
|
|
vcmd.target_system = cmd_mavlink.target_system; |
|
|
|
|
|
|
|
|
|
vcmd.target_component = cmd_mavlink.target_component; |
|
|
|
|
|
|
|
|
|
vcmd.source_system = msg->sysid; |
|
|
|
|
|
|
|
|
|
vcmd.source_component = msg->compid; |
|
|
|
|
|
|
|
|
|
if (_cmd_pub < 0) { |
|
|
|
@ -461,7 +434,6 @@ MavlinkReceiver::handle_message_hil_optical_flow(mavlink_message_t *msg)
@@ -461,7 +434,6 @@ MavlinkReceiver::handle_message_hil_optical_flow(mavlink_message_t *msg)
|
|
|
|
|
|
|
|
|
|
if (_range_pub < 0) { |
|
|
|
|
_range_pub = orb_advertise(ORB_ID(sensor_range_finder), &r); |
|
|
|
|
|
|
|
|
|
} else { |
|
|
|
|
orb_publish(ORB_ID(sensor_range_finder), _range_pub, &r); |
|
|
|
|
} |
|
|
|
@ -546,24 +518,19 @@ MavlinkReceiver::handle_message_set_position_target_local_ned(mavlink_message_t
@@ -546,24 +518,19 @@ MavlinkReceiver::handle_message_set_position_target_local_ned(mavlink_message_t
|
|
|
|
|
case MAV_FRAME_LOCAL_NED: |
|
|
|
|
offboard_control_sp.mode = OFFBOARD_CONTROL_MODE_DIRECT_LOCAL_NED; |
|
|
|
|
break; |
|
|
|
|
|
|
|
|
|
case MAV_FRAME_LOCAL_OFFSET_NED: |
|
|
|
|
offboard_control_sp.mode = OFFBOARD_CONTROL_MODE_DIRECT_LOCAL_OFFSET_NED; |
|
|
|
|
break; |
|
|
|
|
|
|
|
|
|
case MAV_FRAME_BODY_NED: |
|
|
|
|
offboard_control_sp.mode = OFFBOARD_CONTROL_MODE_DIRECT_BODY_NED; |
|
|
|
|
break; |
|
|
|
|
|
|
|
|
|
case MAV_FRAME_BODY_OFFSET_NED: |
|
|
|
|
offboard_control_sp.mode = OFFBOARD_CONTROL_MODE_DIRECT_BODY_OFFSET_NED; |
|
|
|
|
break; |
|
|
|
|
|
|
|
|
|
default: |
|
|
|
|
/* invalid setpoint, avoid publishing */ |
|
|
|
|
return; |
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
offboard_control_sp.position[0] = set_position_target_local_ned.x; |
|
|
|
|
offboard_control_sp.position[1] = set_position_target_local_ned.y; |
|
|
|
|
offboard_control_sp.position[2] = set_position_target_local_ned.z; |
|
|
|
@ -589,13 +556,11 @@ MavlinkReceiver::handle_message_set_position_target_local_ned(mavlink_message_t
@@ -589,13 +556,11 @@ MavlinkReceiver::handle_message_set_position_target_local_ned(mavlink_message_t
|
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
offboard_control_sp.ignore &= ~(1 << OFB_IGN_BIT_YAW); |
|
|
|
|
|
|
|
|
|
if (set_position_target_local_ned.type_mask & (1 << 10)) { |
|
|
|
|
offboard_control_sp.ignore |= (1 << OFB_IGN_BIT_YAW); |
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
offboard_control_sp.ignore &= ~(1 << OFB_IGN_BIT_YAWRATE); |
|
|
|
|
|
|
|
|
|
if (set_position_target_local_ned.type_mask & (1 << 11)) { |
|
|
|
|
offboard_control_sp.ignore |= (1 << OFB_IGN_BIT_YAWRATE); |
|
|
|
|
} |
|
|
|
@ -614,11 +579,9 @@ MavlinkReceiver::handle_message_set_position_target_local_ned(mavlink_message_t
@@ -614,11 +579,9 @@ MavlinkReceiver::handle_message_set_position_target_local_ned(mavlink_message_t
|
|
|
|
|
if (_mavlink->get_forward_externalsp()) { |
|
|
|
|
bool updated; |
|
|
|
|
orb_check(_control_mode_sub, &updated); |
|
|
|
|
|
|
|
|
|
if (updated) { |
|
|
|
|
orb_copy(ORB_ID(vehicle_control_mode), _control_mode_sub, &_control_mode); |
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
if (_control_mode.flag_control_offboard_enabled) { |
|
|
|
|
if (offboard_control_sp.isForceSetpoint && |
|
|
|
|
offboard_control_sp_ignore_position_all(offboard_control_sp) && |
|
|
|
@ -629,15 +592,12 @@ MavlinkReceiver::handle_message_set_position_target_local_ned(mavlink_message_t
@@ -629,15 +592,12 @@ MavlinkReceiver::handle_message_set_position_target_local_ned(mavlink_message_t
|
|
|
|
|
force_sp.x = offboard_control_sp.acceleration[0]; |
|
|
|
|
force_sp.y = offboard_control_sp.acceleration[1]; |
|
|
|
|
force_sp.z = offboard_control_sp.acceleration[2]; |
|
|
|
|
|
|
|
|
|
//XXX: yaw
|
|
|
|
|
if (_force_sp_pub < 0) { |
|
|
|
|
_force_sp_pub = orb_advertise(ORB_ID(vehicle_force_setpoint), &force_sp); |
|
|
|
|
|
|
|
|
|
} else { |
|
|
|
|
orb_publish(ORB_ID(vehicle_force_setpoint), _force_sp_pub, &force_sp); |
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
} else { |
|
|
|
|
/* It's not a pure force setpoint: publish to setpoint triplet topic */ |
|
|
|
|
struct position_setpoint_triplet_s pos_sp_triplet; |
|
|
|
@ -654,7 +614,6 @@ MavlinkReceiver::handle_message_set_position_target_local_ned(mavlink_message_t
@@ -654,7 +614,6 @@ MavlinkReceiver::handle_message_set_position_target_local_ned(mavlink_message_t
|
|
|
|
|
pos_sp_triplet.current.x = offboard_control_sp.position[0]; |
|
|
|
|
pos_sp_triplet.current.y = offboard_control_sp.position[1]; |
|
|
|
|
pos_sp_triplet.current.z = offboard_control_sp.position[2]; |
|
|
|
|
|
|
|
|
|
} else { |
|
|
|
|
pos_sp_triplet.current.position_valid = false; |
|
|
|
|
} |
|
|
|
@ -667,7 +626,6 @@ MavlinkReceiver::handle_message_set_position_target_local_ned(mavlink_message_t
@@ -667,7 +626,6 @@ MavlinkReceiver::handle_message_set_position_target_local_ned(mavlink_message_t
|
|
|
|
|
pos_sp_triplet.current.vx = offboard_control_sp.velocity[0]; |
|
|
|
|
pos_sp_triplet.current.vy = offboard_control_sp.velocity[1]; |
|
|
|
|
pos_sp_triplet.current.vz = offboard_control_sp.velocity[2]; |
|
|
|
|
|
|
|
|
|
} else { |
|
|
|
|
pos_sp_triplet.current.velocity_valid = false; |
|
|
|
|
} |
|
|
|
@ -708,14 +666,12 @@ MavlinkReceiver::handle_message_set_position_target_local_ned(mavlink_message_t
@@ -708,14 +666,12 @@ MavlinkReceiver::handle_message_set_position_target_local_ned(mavlink_message_t
|
|
|
|
|
} else { |
|
|
|
|
pos_sp_triplet.current.yawspeed_valid = false; |
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
//XXX handle global pos setpoints (different MAV frames)
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
if (_pos_sp_triplet_pub < 0) { |
|
|
|
|
_pos_sp_triplet_pub = orb_advertise(ORB_ID(position_setpoint_triplet), |
|
|
|
|
&pos_sp_triplet); |
|
|
|
|
|
|
|
|
|
} else { |
|
|
|
|
orb_publish(ORB_ID(position_setpoint_triplet), _pos_sp_triplet_pub, |
|
|
|
|
&pos_sp_triplet); |
|
|
|
@ -785,7 +741,6 @@ MavlinkReceiver::handle_message_set_attitude_target(mavlink_message_t *msg)
@@ -785,7 +741,6 @@ MavlinkReceiver::handle_message_set_attitude_target(mavlink_message_t *msg)
|
|
|
|
|
for (int i = 0; i < 4; i++) { |
|
|
|
|
offboard_control_sp.attitude[i] = set_attitude_target.q[i]; |
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
offboard_control_sp.attitude_rate[0] = set_attitude_target.body_roll_rate; |
|
|
|
|
offboard_control_sp.attitude_rate[1] = set_attitude_target.body_pitch_rate; |
|
|
|
|
offboard_control_sp.attitude_rate[2] = set_attitude_target.body_yaw_rate; |
|
|
|
@ -795,7 +750,6 @@ MavlinkReceiver::handle_message_set_attitude_target(mavlink_message_t *msg)
@@ -795,7 +750,6 @@ MavlinkReceiver::handle_message_set_attitude_target(mavlink_message_t *msg)
|
|
|
|
|
offboard_control_sp.ignore &= ~(1 << (i + OFB_IGN_BIT_BODYRATE_X)); |
|
|
|
|
offboard_control_sp.ignore |= (set_attitude_target.type_mask & (1 << i)) << OFB_IGN_BIT_BODYRATE_X; |
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
/* set correct ignore flags for thrust field: copy from mavlink message */ |
|
|
|
|
offboard_control_sp.ignore &= ~(1 << OFB_IGN_BIT_THRUST); |
|
|
|
|
offboard_control_sp.ignore |= ((set_attitude_target.type_mask & (1 << 6)) << OFB_IGN_BIT_THRUST); |
|
|
|
@ -805,7 +759,7 @@ MavlinkReceiver::handle_message_set_attitude_target(mavlink_message_t *msg)
@@ -805,7 +759,7 @@ MavlinkReceiver::handle_message_set_attitude_target(mavlink_message_t *msg)
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
offboard_control_sp.timestamp = hrt_absolute_time(); |
|
|
|
|
offboard_control_sp.mode = OFFBOARD_CONTROL_MODE_DIRECT_ATTITUDE; //XXX handle rate control mode
|
|
|
|
|
offboard_control_sp.mode =OFFBOARD_CONTROL_MODE_DIRECT_ATTITUDE; //XXX handle rate control mode
|
|
|
|
|
|
|
|
|
|
if (_offboard_control_sp_pub < 0) { |
|
|
|
|
_offboard_control_sp_pub = orb_advertise(ORB_ID(offboard_control_setpoint), &offboard_control_sp); |
|
|
|
@ -819,7 +773,6 @@ MavlinkReceiver::handle_message_set_attitude_target(mavlink_message_t *msg)
@@ -819,7 +773,6 @@ MavlinkReceiver::handle_message_set_attitude_target(mavlink_message_t *msg)
|
|
|
|
|
if (_mavlink->get_forward_externalsp()) { |
|
|
|
|
bool updated; |
|
|
|
|
orb_check(_control_mode_sub, &updated); |
|
|
|
|
|
|
|
|
|
if (updated) { |
|
|
|
|
orb_copy(ORB_ID(vehicle_control_mode), _control_mode_sub, &_control_mode); |
|
|
|
|
} |
|
|
|
@ -838,10 +791,8 @@ MavlinkReceiver::handle_message_set_attitude_target(mavlink_message_t *msg)
@@ -838,10 +791,8 @@ MavlinkReceiver::handle_message_set_attitude_target(mavlink_message_t *msg)
|
|
|
|
|
att_sp.thrust = set_attitude_target.thrust; |
|
|
|
|
memcpy(att_sp.q_d, set_attitude_target.q, sizeof(att_sp.q_d)); |
|
|
|
|
att_sp.q_d_valid = true; |
|
|
|
|
|
|
|
|
|
if (_att_sp_pub < 0) { |
|
|
|
|
_att_sp_pub = orb_advertise(ORB_ID(vehicle_attitude_setpoint), &att_sp); |
|
|
|
|
|
|
|
|
|
} else { |
|
|
|
|
orb_publish(ORB_ID(vehicle_attitude_setpoint), _att_sp_pub, &att_sp); |
|
|
|
|
} |
|
|
|
@ -860,7 +811,6 @@ MavlinkReceiver::handle_message_set_attitude_target(mavlink_message_t *msg)
@@ -860,7 +811,6 @@ MavlinkReceiver::handle_message_set_attitude_target(mavlink_message_t *msg)
|
|
|
|
|
|
|
|
|
|
if (_att_sp_pub < 0) { |
|
|
|
|
_rates_sp_pub = orb_advertise(ORB_ID(vehicle_rates_setpoint), &rates_sp); |
|
|
|
|
|
|
|
|
|
} else { |
|
|
|
|
orb_publish(ORB_ID(vehicle_rates_setpoint), _rates_sp_pub, &rates_sp); |
|
|
|
|
} |
|
|
|
@ -919,8 +869,7 @@ MavlinkReceiver::handle_message_manual_control(mavlink_message_t *msg)
@@ -919,8 +869,7 @@ MavlinkReceiver::handle_message_manual_control(mavlink_message_t *msg)
|
|
|
|
|
manual.r = man.r / 1000.0f; |
|
|
|
|
manual.z = man.z / 1000.0f; |
|
|
|
|
|
|
|
|
|
warnx("pitch: %.2f, roll: %.2f, yaw: %.2f, throttle: %.2f", (double)manual.x, (double)manual.y, (double)manual.r, |
|
|
|
|
(double)manual.z); |
|
|
|
|
warnx("pitch: %.2f, roll: %.2f, yaw: %.2f, throttle: %.2f", (double)manual.x, (double)manual.y, (double)manual.r, (double)manual.z); |
|
|
|
|
|
|
|
|
|
if (_manual_pub < 0) { |
|
|
|
|
_manual_pub = orb_advertise(ORB_ID(manual_control_setpoint), &manual); |
|
|
|
|