diff --git a/ArduCopter/Copter.h b/ArduCopter/Copter.h index eb7618a1cb..01f3ebd19b 100644 --- a/ArduCopter/Copter.h +++ b/ArduCopter/Copter.h @@ -760,7 +760,6 @@ private: void gcs_send_deferred(void); void send_fence_status(mavlink_channel_t chan); void send_extended_status1(mavlink_channel_t chan); - void send_location(mavlink_channel_t chan); void send_nav_controller_output(mavlink_channel_t chan); void send_simstate(mavlink_channel_t chan); void send_vfr_hud(mavlink_channel_t chan); diff --git a/ArduCopter/GCS_Mavlink.cpp b/ArduCopter/GCS_Mavlink.cpp index 010f030848..3c3fcfcff2 100644 --- a/ArduCopter/GCS_Mavlink.cpp +++ b/ArduCopter/GCS_Mavlink.cpp @@ -132,24 +132,6 @@ NOINLINE void Copter::send_extended_status1(mavlink_channel_t chan) 0, 0, 0, 0); } -void NOINLINE Copter::send_location(mavlink_channel_t chan) -{ - const uint32_t now = AP_HAL::millis(); - Vector3f vel; - ahrs.get_velocity_NED(vel); - mavlink_msg_global_position_int_send( - chan, - now, - current_loc.lat, // in 1E7 degrees - current_loc.lng, // in 1E7 degrees - (ahrs.get_home().alt + current_loc.alt) * 10UL, // millimeters above sea level - current_loc.alt * 10, // millimeters above ground - vel.x * 100, // X speed cm/s (+ve North) - vel.y * 100, // Y speed cm/s (+ve East) - vel.z * 100, // Z speed cm/s (+ve Down) - ahrs.yaw_sensor); // compass heading in 1/100 degree -} - void NOINLINE Copter::send_nav_controller_output(mavlink_channel_t chan) { const Vector3f &targets = attitude_control->get_att_target_euler_cd(); @@ -305,11 +287,6 @@ bool GCS_MAVLINK_Copter::try_send_message(enum ap_message id) } break; - case MSG_LOCATION: - CHECK_PAYLOAD_SIZE(GLOBAL_POSITION_INT); - copter.send_location(chan); - break; - case MSG_NAV_CONTROLLER_OUTPUT: CHECK_PAYLOAD_SIZE(NAV_CONTROLLER_OUTPUT); copter.send_nav_controller_output(chan);