mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-23 16:23:56 -04:00
uncrustify ArduCopter/GCS_Mavlink.pde
This commit is contained in:
parent
fef945e2cb
commit
e8760bec78
@ -13,19 +13,19 @@ static bool mavlink_active;
|
||||
|
||||
|
||||
// check if a message will fit in the payload space available
|
||||
#define CHECK_PAYLOAD_SIZE(id) if (payload_space < MAVLINK_MSG_ID_## id ##_LEN) return false
|
||||
#define CHECK_PAYLOAD_SIZE(id) if (payload_space < MAVLINK_MSG_ID_ ## id ## _LEN) return false
|
||||
|
||||
// prototype this for use inside the GCS class
|
||||
static void gcs_send_text_fmt(const prog_char_t *fmt, ...);
|
||||
|
||||
/*
|
||||
!!NOTE!!
|
||||
|
||||
the use of NOINLINE separate functions for each message type avoids
|
||||
a compiler bug in gcc that would cause it to use far more stack
|
||||
space than is needed. Without the NOINLINE we use the sum of the
|
||||
stack needed for each message type. Please be careful to follow the
|
||||
pattern below when adding any new messages
|
||||
* !!NOTE!!
|
||||
*
|
||||
* the use of NOINLINE separate functions for each message type avoids
|
||||
* a compiler bug in gcc that would cause it to use far more stack
|
||||
* space than is needed. Without the NOINLINE we use the sum of the
|
||||
* stack needed for each message type. Please be careful to follow the
|
||||
* pattern below when adding any new messages
|
||||
*/
|
||||
|
||||
static NOINLINE void send_heartbeat(mavlink_channel_t chan)
|
||||
@ -165,8 +165,8 @@ static NOINLINE void send_extended_status1(mavlink_channel_t chan, uint16_t pack
|
||||
|
||||
if (g.battery_monitoring == 3) {
|
||||
/*setting a out-of-range value.
|
||||
It informs to external devices that
|
||||
it cannot be calculated properly just by voltage*/
|
||||
* It informs to external devices that
|
||||
* it cannot be calculated properly just by voltage*/
|
||||
battery_remaining = 150;
|
||||
}
|
||||
|
||||
@ -282,7 +282,7 @@ static void NOINLINE send_servo_out(mavlink_channel_t chan)
|
||||
// normalized values scaled to -10000 to 10000
|
||||
// This is used for HIL. Do not change without discussing with HIL maintainers
|
||||
|
||||
#if FRAME_CONFIG == HELI_FRAME
|
||||
#if FRAME_CONFIG == HELI_FRAME
|
||||
|
||||
mavlink_msg_rc_channels_scaled_send(
|
||||
chan,
|
||||
@ -297,10 +297,10 @@ static void NOINLINE send_servo_out(mavlink_channel_t chan)
|
||||
0,
|
||||
0,
|
||||
rssi);
|
||||
#else
|
||||
#else
|
||||
#if X_PLANE == ENABLED
|
||||
/* update by JLN for X-Plane HIL */
|
||||
if(motors.armed() && motors.auto_armed()){
|
||||
if(motors.armed() && motors.auto_armed()) {
|
||||
mavlink_msg_rc_channels_scaled_send(
|
||||
chan,
|
||||
millis(),
|
||||
@ -345,7 +345,7 @@ static void NOINLINE send_servo_out(mavlink_channel_t chan)
|
||||
10000 * g.rc_4.norm_output(),
|
||||
rssi);
|
||||
#endif
|
||||
#endif
|
||||
#endif
|
||||
}
|
||||
|
||||
static void NOINLINE send_radio_in(mavlink_channel_t chan)
|
||||
@ -693,7 +693,7 @@ void mavlink_send_text(mavlink_channel_t chan, gcs_severity severity, const char
|
||||
chan,
|
||||
severity,
|
||||
str);
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
const AP_Param::GroupInfo GCS_MAVLINK::var_info[] PROGMEM = {
|
||||
@ -711,9 +711,9 @@ const AP_Param::GroupInfo GCS_MAVLINK::var_info[] PROGMEM = {
|
||||
|
||||
|
||||
GCS_MAVLINK::GCS_MAVLINK() :
|
||||
packet_drops(0),
|
||||
waypoint_send_timeout(1000), // 1 second
|
||||
waypoint_receive_timeout(1000) // 1 second
|
||||
packet_drops(0),
|
||||
waypoint_send_timeout(1000), // 1 second
|
||||
waypoint_receive_timeout(1000) // 1 second
|
||||
{
|
||||
|
||||
}
|
||||
@ -747,7 +747,7 @@ GCS_MAVLINK::update(void)
|
||||
|
||||
#if CLI_ENABLED == ENABLED
|
||||
/* allow CLI to be started by hitting enter 3 times, if no
|
||||
heartbeat packets have been received */
|
||||
* heartbeat packets have been received */
|
||||
if (mavlink_active == false) {
|
||||
if (c == '\n' || c == '\r') {
|
||||
crlf_count++;
|
||||
@ -784,12 +784,12 @@ GCS_MAVLINK::update(void)
|
||||
}
|
||||
|
||||
// stop waypoint sending if timeout
|
||||
if (waypoint_sending && (tnow - waypoint_timelast_send) > waypoint_send_timeout){
|
||||
if (waypoint_sending && (tnow - waypoint_timelast_send) > waypoint_send_timeout) {
|
||||
waypoint_sending = false;
|
||||
}
|
||||
|
||||
// stop waypoint receiving if timeout
|
||||
if (waypoint_receiving && (tnow - waypoint_timelast_receive) > waypoint_receive_timeout){
|
||||
if (waypoint_receiving && (tnow - waypoint_timelast_receive) > waypoint_receive_timeout) {
|
||||
waypoint_receiving = false;
|
||||
}
|
||||
}
|
||||
@ -899,7 +899,7 @@ GCS_MAVLINK::data_stream_send(void)
|
||||
send_message(MSG_AHRS);
|
||||
send_message(MSG_HWSTATUS);
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
|
||||
|
||||
@ -950,7 +950,7 @@ void GCS_MAVLINK::handleMessage(mavlink_message_t* msg)
|
||||
else
|
||||
break;
|
||||
|
||||
switch(packet.req_stream_id){
|
||||
switch(packet.req_stream_id) {
|
||||
|
||||
case MAV_DATA_STREAM_ALL:
|
||||
streamRateRawSensors = freq;
|
||||
@ -1099,14 +1099,14 @@ void GCS_MAVLINK::handleMessage(mavlink_message_t* msg)
|
||||
}
|
||||
|
||||
/*case MAVLINK_MSG_ID_SET_NAV_MODE:
|
||||
{
|
||||
// decode
|
||||
mavlink_set_nav_mode_t packet;
|
||||
mavlink_msg_set_nav_mode_decode(msg, &packet);
|
||||
// To set some flight modes we must first receive a "set nav mode" message and then a "set mode" message
|
||||
mav_nav = packet.nav_mode;
|
||||
break;
|
||||
}
|
||||
* {
|
||||
* // decode
|
||||
* mavlink_set_nav_mode_t packet;
|
||||
* mavlink_msg_set_nav_mode_decode(msg, &packet);
|
||||
* // To set some flight modes we must first receive a "set nav mode" message and then a "set mode" message
|
||||
* mav_nav = packet.nav_mode;
|
||||
* break;
|
||||
* }
|
||||
*/
|
||||
case MAVLINK_MSG_ID_MISSION_REQUEST_LIST: //43
|
||||
{
|
||||
@ -1160,7 +1160,7 @@ void GCS_MAVLINK::handleMessage(mavlink_message_t* msg)
|
||||
frame = MAV_FRAME_GLOBAL; // reference frame
|
||||
}
|
||||
|
||||
float param1 = 0, param2 = 0 , param3 = 0, param4 = 0;
|
||||
float param1 = 0, param2 = 0, param3 = 0, param4 = 0;
|
||||
|
||||
// time that the mav should loiter in milliseconds
|
||||
uint8_t current = 0; // 1 (true), 0 (false)
|
||||
@ -1334,7 +1334,7 @@ void GCS_MAVLINK::handleMessage(mavlink_message_t* msg)
|
||||
g.command_total.set_and_save(1);
|
||||
|
||||
// send acknowledgement 3 times to makes sure it is received
|
||||
for (int16_t i=0;i<3;i++)
|
||||
for (int16_t i=0; i<3; i++)
|
||||
mavlink_msg_mission_ack_send(chan, msg->sysid, msg->compid, type);
|
||||
|
||||
break;
|
||||
@ -1402,37 +1402,37 @@ void GCS_MAVLINK::handleMessage(mavlink_message_t* msg)
|
||||
tell_command.id = packet.command;
|
||||
|
||||
/*
|
||||
switch (packet.frame){
|
||||
|
||||
case MAV_FRAME_MISSION:
|
||||
case MAV_FRAME_GLOBAL:
|
||||
{
|
||||
tell_command.lat = 1.0e7*packet.x; // in as DD converted to * t7
|
||||
tell_command.lng = 1.0e7*packet.y; // in as DD converted to * t7
|
||||
tell_command.alt = packet.z*1.0e2; // in as m converted to cm
|
||||
tell_command.options = 0; // absolute altitude
|
||||
break;
|
||||
}
|
||||
|
||||
case MAV_FRAME_LOCAL: // local (relative to home position)
|
||||
{
|
||||
tell_command.lat = 1.0e7*ToDeg(packet.x/
|
||||
(radius_of_earth*cos(ToRad(home.lat/1.0e7)))) + home.lat;
|
||||
tell_command.lng = 1.0e7*ToDeg(packet.y/radius_of_earth) + home.lng;
|
||||
tell_command.alt = packet.z*1.0e2;
|
||||
tell_command.options = MASK_OPTIONS_RELATIVE_ALT;
|
||||
break;
|
||||
}
|
||||
//case MAV_FRAME_GLOBAL_RELATIVE_ALT: // absolute lat/lng, relative altitude
|
||||
default:
|
||||
{
|
||||
tell_command.lat = 1.0e7 * packet.x; // in as DD converted to * t7
|
||||
tell_command.lng = 1.0e7 * packet.y; // in as DD converted to * t7
|
||||
tell_command.alt = packet.z * 1.0e2;
|
||||
tell_command.options = MASK_OPTIONS_RELATIVE_ALT; // store altitude relative!! Always!!
|
||||
break;
|
||||
}
|
||||
}
|
||||
* switch (packet.frame){
|
||||
*
|
||||
* case MAV_FRAME_MISSION:
|
||||
* case MAV_FRAME_GLOBAL:
|
||||
* {
|
||||
* tell_command.lat = 1.0e7*packet.x; // in as DD converted to * t7
|
||||
* tell_command.lng = 1.0e7*packet.y; // in as DD converted to * t7
|
||||
* tell_command.alt = packet.z*1.0e2; // in as m converted to cm
|
||||
* tell_command.options = 0; // absolute altitude
|
||||
* break;
|
||||
* }
|
||||
*
|
||||
* case MAV_FRAME_LOCAL: // local (relative to home position)
|
||||
* {
|
||||
* tell_command.lat = 1.0e7*ToDeg(packet.x/
|
||||
* (radius_of_earth*cos(ToRad(home.lat/1.0e7)))) + home.lat;
|
||||
* tell_command.lng = 1.0e7*ToDeg(packet.y/radius_of_earth) + home.lng;
|
||||
* tell_command.alt = packet.z*1.0e2;
|
||||
* tell_command.options = MASK_OPTIONS_RELATIVE_ALT;
|
||||
* break;
|
||||
* }
|
||||
* //case MAV_FRAME_GLOBAL_RELATIVE_ALT: // absolute lat/lng, relative altitude
|
||||
* default:
|
||||
* {
|
||||
* tell_command.lat = 1.0e7 * packet.x; // in as DD converted to * t7
|
||||
* tell_command.lng = 1.0e7 * packet.y; // in as DD converted to * t7
|
||||
* tell_command.alt = packet.z * 1.0e2;
|
||||
* tell_command.options = MASK_OPTIONS_RELATIVE_ALT; // store altitude relative!! Always!!
|
||||
* break;
|
||||
* }
|
||||
* }
|
||||
*/
|
||||
|
||||
// we only are supporting Abs position, relative Alt
|
||||
@ -1501,11 +1501,11 @@ void GCS_MAVLINK::handleMessage(mavlink_message_t* msg)
|
||||
break;
|
||||
}
|
||||
|
||||
if(packet.current == 2){ //current = 2 is a flag to tell us this is a "guided mode" waypoint and not for the mission
|
||||
if(packet.current == 2) { //current = 2 is a flag to tell us this is a "guided mode" waypoint and not for the mission
|
||||
guided_WP = tell_command;
|
||||
|
||||
// add home alt if needed
|
||||
if (guided_WP.options & MASK_OPTIONS_RELATIVE_ALT){
|
||||
if (guided_WP.options & MASK_OPTIONS_RELATIVE_ALT) {
|
||||
guided_WP.alt += home.alt;
|
||||
}
|
||||
|
||||
@ -1540,7 +1540,7 @@ void GCS_MAVLINK::handleMessage(mavlink_message_t* msg)
|
||||
waypoint_timelast_request = 0;
|
||||
waypoint_request_i++;
|
||||
|
||||
if (waypoint_request_i == (uint16_t)g.command_total){
|
||||
if (waypoint_request_i == (uint16_t)g.command_total) {
|
||||
uint8_t type = 0; // ok (0), error(1)
|
||||
|
||||
mavlink_msg_mission_ack_send(
|
||||
@ -1714,30 +1714,30 @@ void GCS_MAVLINK::handleMessage(mavlink_message_t* msg)
|
||||
#endif // HIL_MODE != HIL_MODE_DISABLED
|
||||
|
||||
/*
|
||||
case MAVLINK_MSG_ID_HEARTBEAT:
|
||||
{
|
||||
// We keep track of the last time we received a heartbeat from our GCS for failsafe purposes
|
||||
if(msg->sysid != g.sysid_my_gcs) break;
|
||||
rc_override_fs_timer = millis();
|
||||
break;
|
||||
}
|
||||
|
||||
#if HIL_MODE != HIL_MODE_DISABLED
|
||||
// This is used both as a sensor and to pass the location
|
||||
// in HIL_ATTITUDE mode.
|
||||
case MAVLINK_MSG_ID_GPS_RAW:
|
||||
{
|
||||
// decode
|
||||
mavlink_gps_raw_t packet;
|
||||
mavlink_msg_gps_raw_decode(msg, &packet);
|
||||
|
||||
// set gps hil sensor
|
||||
g_gps->setHIL(packet.usec/1000,packet.lat,packet.lon,packet.alt,
|
||||
packet.v,packet.hdg,0,0);
|
||||
break;
|
||||
}
|
||||
#endif
|
||||
*/
|
||||
* case MAVLINK_MSG_ID_HEARTBEAT:
|
||||
* {
|
||||
* // We keep track of the last time we received a heartbeat from our GCS for failsafe purposes
|
||||
* if(msg->sysid != g.sysid_my_gcs) break;
|
||||
* rc_override_fs_timer = millis();
|
||||
* break;
|
||||
* }
|
||||
*
|
||||
* #if HIL_MODE != HIL_MODE_DISABLED
|
||||
* // This is used both as a sensor and to pass the location
|
||||
* // in HIL_ATTITUDE mode.
|
||||
* case MAVLINK_MSG_ID_GPS_RAW:
|
||||
* {
|
||||
* // decode
|
||||
* mavlink_gps_raw_t packet;
|
||||
* mavlink_msg_gps_raw_decode(msg, &packet);
|
||||
*
|
||||
* // set gps hil sensor
|
||||
* g_gps->setHIL(packet.usec/1000,packet.lat,packet.lon,packet.alt,
|
||||
* packet.v,packet.hdg,0,0);
|
||||
* break;
|
||||
* }
|
||||
* #endif
|
||||
*/
|
||||
#if HIL_MODE == HIL_MODE_SENSORS
|
||||
|
||||
case MAVLINK_MSG_ID_RAW_IMU: // 28
|
||||
@ -1899,9 +1899,9 @@ GCS_MAVLINK::_count_parameters()
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Send the next pending parameter, called from deferred message
|
||||
* handling code
|
||||
*/
|
||||
* @brief Send the next pending parameter, called from deferred message
|
||||
* handling code
|
||||
*/
|
||||
void
|
||||
GCS_MAVLINK::queued_param_send()
|
||||
{
|
||||
@ -1933,9 +1933,9 @@ GCS_MAVLINK::queued_param_send()
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Send the next pending waypoint, called from deferred message
|
||||
* handling code
|
||||
*/
|
||||
* @brief Send the next pending waypoint, called from deferred message
|
||||
* handling code
|
||||
*/
|
||||
void
|
||||
GCS_MAVLINK::queued_waypoint_send()
|
||||
{
|
||||
@ -1950,11 +1950,11 @@ GCS_MAVLINK::queued_waypoint_send()
|
||||
}
|
||||
|
||||
/*
|
||||
a delay() callback that processes MAVLink packets. We set this as the
|
||||
callback in long running library initialisation routines to allow
|
||||
MAVLink to process packets while waiting for the initialisation to
|
||||
complete
|
||||
*/
|
||||
* a delay() callback that processes MAVLink packets. We set this as the
|
||||
* callback in long running library initialisation routines to allow
|
||||
* MAVLink to process packets while waiting for the initialisation to
|
||||
* complete
|
||||
*/
|
||||
static void mavlink_delay(unsigned long t)
|
||||
{
|
||||
uint32_t tstart;
|
||||
@ -1987,16 +1987,16 @@ static void mavlink_delay(unsigned long t)
|
||||
gcs_send_text_P(SEVERITY_LOW, PSTR("Initialising APM..."));
|
||||
}
|
||||
delay(1);
|
||||
#if USB_MUX_PIN > 0
|
||||
#if USB_MUX_PIN > 0
|
||||
check_usb_mux();
|
||||
#endif
|
||||
#endif
|
||||
} while (millis() - tstart < t);
|
||||
|
||||
in_mavlink_delay = false;
|
||||
}
|
||||
|
||||
/*
|
||||
send a message on both GCS links
|
||||
* send a message on both GCS links
|
||||
*/
|
||||
static void gcs_send_message(enum ap_message id)
|
||||
{
|
||||
@ -2007,7 +2007,7 @@ static void gcs_send_message(enum ap_message id)
|
||||
}
|
||||
|
||||
/*
|
||||
send data streams in the given rate range on both links
|
||||
* send data streams in the given rate range on both links
|
||||
*/
|
||||
static void gcs_data_stream_send(void)
|
||||
{
|
||||
@ -2018,7 +2018,7 @@ static void gcs_data_stream_send(void)
|
||||
}
|
||||
|
||||
/*
|
||||
look for incoming commands on the GCS links
|
||||
* look for incoming commands on the GCS links
|
||||
*/
|
||||
static void gcs_update(void)
|
||||
{
|
||||
@ -2045,9 +2045,9 @@ static void gcs_send_text_P(gcs_severity severity, const prog_char_t *str)
|
||||
}
|
||||
|
||||
/*
|
||||
send a low priority formatted message to the GCS
|
||||
only one fits in the queue, so if you send more than one before the
|
||||
last one gets into the serial buffer then the old one will be lost
|
||||
* send a low priority formatted message to the GCS
|
||||
* only one fits in the queue, so if you send more than one before the
|
||||
* last one gets into the serial buffer then the old one will be lost
|
||||
*/
|
||||
static void gcs_send_text_fmt(const prog_char_t *fmt, ...)
|
||||
{
|
||||
|
Loading…
Reference in New Issue
Block a user