mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
remove unsued MSG_LOCAL_LOCATION
this saves us a bit of code
This commit is contained in:
parent
5042ca8e9e
commit
87ddd50c2a
@ -93,8 +93,6 @@ HIL_XPLANE::send_message(uint8_t id, uint32_t param)
|
|||||||
break;
|
break;
|
||||||
case MSG_LOCATION:
|
case MSG_LOCATION:
|
||||||
break;
|
break;
|
||||||
case MSG_LOCAL_LOCATION:
|
|
||||||
break;
|
|
||||||
case MSG_GPS_RAW:
|
case MSG_GPS_RAW:
|
||||||
break;
|
break;
|
||||||
case MSG_SERVO_OUT:
|
case MSG_SERVO_OUT:
|
||||||
|
@ -149,20 +149,6 @@ static void NOINLINE send_nav_controller_output(mavlink_channel_t chan)
|
|||||||
crosstrack_error);
|
crosstrack_error);
|
||||||
}
|
}
|
||||||
|
|
||||||
static void NOINLINE send_local_location(mavlink_channel_t chan)
|
|
||||||
{
|
|
||||||
Matrix3f rot = dcm.get_dcm_matrix(); // neglecting angle of attack for now
|
|
||||||
mavlink_msg_local_position_send(
|
|
||||||
chan,
|
|
||||||
micros(),
|
|
||||||
ToRad((current_loc.lat - home.lat) / 1.0e7) * radius_of_earth,
|
|
||||||
ToRad((current_loc.lng - home.lng) / 1.0e7) * radius_of_earth * cos(ToRad(home.lat / 1.0e7)),
|
|
||||||
(current_loc.alt - home.alt) / 1.0e2,
|
|
||||||
g_gps->ground_speed / 1.0e2 * rot.a.x,
|
|
||||||
g_gps->ground_speed / 1.0e2 * rot.b.x,
|
|
||||||
g_gps->ground_speed / 1.0e2 * rot.c.x);
|
|
||||||
}
|
|
||||||
|
|
||||||
static void NOINLINE send_gps_raw(mavlink_channel_t chan)
|
static void NOINLINE send_gps_raw(mavlink_channel_t chan)
|
||||||
{
|
{
|
||||||
mavlink_msg_gps_raw_send(
|
mavlink_msg_gps_raw_send(
|
||||||
@ -348,11 +334,6 @@ static bool mavlink_try_send_message(mavlink_channel_t chan, uint8_t id, uint16_
|
|||||||
}
|
}
|
||||||
break;
|
break;
|
||||||
|
|
||||||
case MSG_LOCAL_LOCATION:
|
|
||||||
CHECK_PAYLOAD_SIZE(LOCAL_POSITION);
|
|
||||||
send_local_location(chan);
|
|
||||||
break;
|
|
||||||
|
|
||||||
case MSG_GPS_RAW:
|
case MSG_GPS_RAW:
|
||||||
CHECK_PAYLOAD_SIZE(GPS_RAW);
|
CHECK_PAYLOAD_SIZE(GPS_RAW);
|
||||||
send_gps_raw(chan);
|
send_gps_raw(chan);
|
||||||
|
@ -163,7 +163,6 @@
|
|||||||
#define MSG_ATTITUDE_CORRECT 0xb1
|
#define MSG_ATTITUDE_CORRECT 0xb1
|
||||||
#define MSG_POSITION_SET 0xb2
|
#define MSG_POSITION_SET 0xb2
|
||||||
#define MSG_ATTITUDE_SET 0xb3
|
#define MSG_ATTITUDE_SET 0xb3
|
||||||
#define MSG_LOCAL_LOCATION 0xb4
|
|
||||||
#define MSG_RETRY_DEFERRED 0xff
|
#define MSG_RETRY_DEFERRED 0xff
|
||||||
|
|
||||||
#define SEVERITY_LOW 1
|
#define SEVERITY_LOW 1
|
||||||
|
Loading…
Reference in New Issue
Block a user