|
|
|
@ -91,7 +91,7 @@ void GCS_MAVLINK_Copter::send_position_target_global_int()
@@ -91,7 +91,7 @@ void GCS_MAVLINK_Copter::send_position_target_global_int()
|
|
|
|
|
static constexpr uint16_t POSITION_TARGET_TYPEMASK_LAST_BYTE = 0xF000; |
|
|
|
|
static constexpr uint16_t TYPE_MASK = POSITION_TARGET_TYPEMASK_VX_IGNORE | POSITION_TARGET_TYPEMASK_VY_IGNORE | POSITION_TARGET_TYPEMASK_VZ_IGNORE | |
|
|
|
|
POSITION_TARGET_TYPEMASK_AX_IGNORE | POSITION_TARGET_TYPEMASK_AY_IGNORE | POSITION_TARGET_TYPEMASK_AZ_IGNORE | |
|
|
|
|
POSITION_TARGET_TYPEMASK_FORCE_SET | POSITION_TARGET_TYPEMASK_YAW_IGNORE | POSITION_TARGET_TYPEMASK_YAW_RATE_IGNORE | POSITION_TARGET_TYPEMASK_LAST_BYTE; |
|
|
|
|
POSITION_TARGET_TYPEMASK_YAW_IGNORE | POSITION_TARGET_TYPEMASK_YAW_RATE_IGNORE | POSITION_TARGET_TYPEMASK_LAST_BYTE; |
|
|
|
|
mavlink_msg_position_target_global_int_send( |
|
|
|
|
chan, |
|
|
|
|
AP_HAL::millis(), // time_boot_ms
|
|
|
|
@ -131,25 +131,25 @@ void GCS_MAVLINK_Copter::send_position_target_local_ned()
@@ -131,25 +131,25 @@ void GCS_MAVLINK_Copter::send_position_target_local_ned()
|
|
|
|
|
case ModeGuided::SubMode::WP: |
|
|
|
|
type_mask = POSITION_TARGET_TYPEMASK_VX_IGNORE | POSITION_TARGET_TYPEMASK_VY_IGNORE | POSITION_TARGET_TYPEMASK_VZ_IGNORE | |
|
|
|
|
POSITION_TARGET_TYPEMASK_AX_IGNORE | POSITION_TARGET_TYPEMASK_AY_IGNORE | POSITION_TARGET_TYPEMASK_AZ_IGNORE | |
|
|
|
|
POSITION_TARGET_TYPEMASK_FORCE_SET | POSITION_TARGET_TYPEMASK_YAW_IGNORE| POSITION_TARGET_TYPEMASK_YAW_RATE_IGNORE; // ignore everything except position
|
|
|
|
|
POSITION_TARGET_TYPEMASK_YAW_IGNORE| POSITION_TARGET_TYPEMASK_YAW_RATE_IGNORE; // ignore everything except position
|
|
|
|
|
target_pos = copter.mode_guided.get_target_pos().tofloat() * 0.01; // convert to metres
|
|
|
|
|
break; |
|
|
|
|
case ModeGuided::SubMode::PosVelAccel: |
|
|
|
|
type_mask = POSITION_TARGET_TYPEMASK_FORCE_SET | POSITION_TARGET_TYPEMASK_YAW_IGNORE| POSITION_TARGET_TYPEMASK_YAW_RATE_IGNORE; // ignore everything except position, velocity & acceleration
|
|
|
|
|
type_mask = POSITION_TARGET_TYPEMASK_YAW_IGNORE| POSITION_TARGET_TYPEMASK_YAW_RATE_IGNORE; // ignore everything except position, velocity & acceleration
|
|
|
|
|
target_pos = copter.mode_guided.get_target_pos().tofloat() * 0.01; // convert to metres
|
|
|
|
|
target_vel = copter.mode_guided.get_target_vel() * 0.01f; // convert to metres/s
|
|
|
|
|
target_accel = copter.mode_guided.get_target_accel() * 0.01f; // convert to metres/s/s
|
|
|
|
|
break; |
|
|
|
|
case ModeGuided::SubMode::VelAccel: |
|
|
|
|
type_mask = POSITION_TARGET_TYPEMASK_X_IGNORE | POSITION_TARGET_TYPEMASK_Y_IGNORE | POSITION_TARGET_TYPEMASK_Z_IGNORE | |
|
|
|
|
POSITION_TARGET_TYPEMASK_FORCE_SET | POSITION_TARGET_TYPEMASK_YAW_IGNORE| POSITION_TARGET_TYPEMASK_YAW_RATE_IGNORE; // ignore everything except velocity & acceleration
|
|
|
|
|
POSITION_TARGET_TYPEMASK_YAW_IGNORE| POSITION_TARGET_TYPEMASK_YAW_RATE_IGNORE; // ignore everything except velocity & acceleration
|
|
|
|
|
target_vel = copter.mode_guided.get_target_vel() * 0.01f; // convert to metres/s
|
|
|
|
|
target_accel = copter.mode_guided.get_target_accel() * 0.01f; // convert to metres/s/s
|
|
|
|
|
break; |
|
|
|
|
case ModeGuided::SubMode::Accel: |
|
|
|
|
type_mask = POSITION_TARGET_TYPEMASK_X_IGNORE | POSITION_TARGET_TYPEMASK_Y_IGNORE | POSITION_TARGET_TYPEMASK_Z_IGNORE | |
|
|
|
|
POSITION_TARGET_TYPEMASK_VX_IGNORE | POSITION_TARGET_TYPEMASK_VY_IGNORE | POSITION_TARGET_TYPEMASK_VZ_IGNORE | |
|
|
|
|
POSITION_TARGET_TYPEMASK_FORCE_SET | POSITION_TARGET_TYPEMASK_YAW_IGNORE| POSITION_TARGET_TYPEMASK_YAW_RATE_IGNORE; // ignore everything except velocity & acceleration
|
|
|
|
|
POSITION_TARGET_TYPEMASK_YAW_IGNORE| POSITION_TARGET_TYPEMASK_YAW_RATE_IGNORE; // ignore everything except velocity & acceleration
|
|
|
|
|
target_accel = copter.mode_guided.get_target_accel() * 0.01f; // convert to metres/s/s
|
|
|
|
|
break; |
|
|
|
|
} |
|
|
|
|