mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-11 02:18:29 -04:00
Rover: gcs_mavlink.cpp correct whitespace, remove tabs
This commit is contained in:
parent
aea1c81437
commit
d33f67e0c4
@ -483,7 +483,6 @@ bool GCS_MAVLINK_Rover::try_send_message(enum ap_message id)
|
|||||||
case MSG_RPM:
|
case MSG_RPM:
|
||||||
case MSG_POSITION_TARGET_GLOBAL_INT:
|
case MSG_POSITION_TARGET_GLOBAL_INT:
|
||||||
break; // just here to prevent a warning
|
break; // just here to prevent a warning
|
||||||
|
|
||||||
}
|
}
|
||||||
return true;
|
return true;
|
||||||
}
|
}
|
||||||
@ -726,7 +725,6 @@ void GCS_MAVLINK_Rover::handle_change_alt_request(AP_Mission::Mission_Command &c
|
|||||||
void GCS_MAVLINK_Rover::handleMessage(mavlink_message_t* msg)
|
void GCS_MAVLINK_Rover::handleMessage(mavlink_message_t* msg)
|
||||||
{
|
{
|
||||||
switch (msg->msgid) {
|
switch (msg->msgid) {
|
||||||
|
|
||||||
case MAVLINK_MSG_ID_REQUEST_DATA_STREAM:
|
case MAVLINK_MSG_ID_REQUEST_DATA_STREAM:
|
||||||
{
|
{
|
||||||
handle_request_data_stream(msg, true);
|
handle_request_data_stream(msg, true);
|
||||||
@ -806,7 +804,6 @@ void GCS_MAVLINK_Rover::handleMessage(mavlink_message_t* msg)
|
|||||||
// do command
|
// do command
|
||||||
|
|
||||||
switch (packet.command) {
|
switch (packet.command) {
|
||||||
|
|
||||||
case MAV_CMD_START_RX_PAIR:
|
case MAV_CMD_START_RX_PAIR:
|
||||||
result = handle_rc_bind(packet);
|
result = handle_rc_bind(packet);
|
||||||
break;
|
break;
|
||||||
@ -1476,7 +1473,6 @@ void GCS_MAVLINK_Rover::handleMessage(mavlink_message_t* msg)
|
|||||||
default:
|
default:
|
||||||
handle_common_message(msg);
|
handle_common_message(msg);
|
||||||
break;
|
break;
|
||||||
|
|
||||||
} // end switch
|
} // end switch
|
||||||
} // end handle mavlink
|
} // end handle mavlink
|
||||||
|
|
||||||
@ -1521,7 +1517,7 @@ void Rover::mavlink_delay_cb()
|
|||||||
*/
|
*/
|
||||||
void Rover::gcs_send_message(enum ap_message id)
|
void Rover::gcs_send_message(enum ap_message id)
|
||||||
{
|
{
|
||||||
for (uint8_t i=0; i<num_gcs; i++) {
|
for (uint8_t i=0; i < num_gcs; i++) {
|
||||||
if (gcs[i].initialised) {
|
if (gcs[i].initialised) {
|
||||||
gcs[i].send_message(id);
|
gcs[i].send_message(id);
|
||||||
}
|
}
|
||||||
@ -1533,7 +1529,7 @@ void Rover::gcs_send_message(enum ap_message id)
|
|||||||
*/
|
*/
|
||||||
void Rover::gcs_send_mission_item_reached_message(uint16_t mission_index)
|
void Rover::gcs_send_mission_item_reached_message(uint16_t mission_index)
|
||||||
{
|
{
|
||||||
for (uint8_t i=0; i<num_gcs; i++) {
|
for (uint8_t i=0; i < num_gcs; i++) {
|
||||||
if (gcs[i].initialised) {
|
if (gcs[i].initialised) {
|
||||||
gcs[i].mission_item_reached_index = mission_index;
|
gcs[i].mission_item_reached_index = mission_index;
|
||||||
gcs[i].send_message(MSG_MISSION_ITEM_REACHED);
|
gcs[i].send_message(MSG_MISSION_ITEM_REACHED);
|
||||||
@ -1546,7 +1542,7 @@ void Rover::gcs_send_mission_item_reached_message(uint16_t mission_index)
|
|||||||
*/
|
*/
|
||||||
void Rover::gcs_data_stream_send(void)
|
void Rover::gcs_data_stream_send(void)
|
||||||
{
|
{
|
||||||
for (uint8_t i=0; i<num_gcs; i++) {
|
for (uint8_t i=0; i < num_gcs; i++) {
|
||||||
if (gcs[i].initialised) {
|
if (gcs[i].initialised) {
|
||||||
gcs[i].data_stream_send();
|
gcs[i].data_stream_send();
|
||||||
}
|
}
|
||||||
@ -1558,7 +1554,7 @@ void Rover::gcs_data_stream_send(void)
|
|||||||
*/
|
*/
|
||||||
void Rover::gcs_update(void)
|
void Rover::gcs_update(void)
|
||||||
{
|
{
|
||||||
for (uint8_t i=0; i<num_gcs; i++) {
|
for (uint8_t i=0; i < num_gcs; i++) {
|
||||||
if (gcs[i].initialised) {
|
if (gcs[i].initialised) {
|
||||||
#if CLI_ENABLED == ENABLED
|
#if CLI_ENABLED == ENABLED
|
||||||
gcs[i].update(g.cli_enabled == 1 ? FUNCTOR_BIND_MEMBER(&Rover::run_cli, void, AP_HAL::UARTDriver *) : nullptr);
|
gcs[i].update(g.cli_enabled == 1 ? FUNCTOR_BIND_MEMBER(&Rover::run_cli, void, AP_HAL::UARTDriver *) : nullptr);
|
||||||
|
Loading…
Reference in New Issue
Block a user