Rover: commands_logic.cpp correct whitespace, remove tabs
This commit is contained in:
parent
d68c7f935b
commit
0c420f931f
@ -15,13 +15,13 @@ bool Rover::start_command(const AP_Mission::Mission_Command& cmd)
|
|||||||
return false;
|
return false;
|
||||||
}
|
}
|
||||||
|
|
||||||
gcs_send_text_fmt(MAV_SEVERITY_INFO, "Executing command ID #%i",cmd.id);
|
gcs_send_text_fmt(MAV_SEVERITY_INFO, "Executing command ID #%i", cmd.id);
|
||||||
|
|
||||||
// remember the course of our next navigation leg
|
// remember the course of our next navigation leg
|
||||||
next_navigation_leg_cd = mission.get_next_ground_course_cd(0);
|
next_navigation_leg_cd = mission.get_next_ground_course_cd(0);
|
||||||
|
|
||||||
switch (cmd.id) {
|
switch (cmd.id) {
|
||||||
case MAV_CMD_NAV_WAYPOINT: // Navigate to Waypoint
|
case MAV_CMD_NAV_WAYPOINT: // Navigate to Waypoint
|
||||||
do_nav_wp(cmd);
|
do_nav_wp(cmd);
|
||||||
break;
|
break;
|
||||||
|
|
||||||
@ -161,7 +161,6 @@ Return true if we do not recognize the command so that we move on to the next co
|
|||||||
bool Rover::verify_command(const AP_Mission::Mission_Command& cmd)
|
bool Rover::verify_command(const AP_Mission::Mission_Command& cmd)
|
||||||
{
|
{
|
||||||
switch (cmd.id) {
|
switch (cmd.id) {
|
||||||
|
|
||||||
case MAV_CMD_NAV_WAYPOINT:
|
case MAV_CMD_NAV_WAYPOINT:
|
||||||
return verify_nav_wp(cmd);
|
return verify_nav_wp(cmd);
|
||||||
|
|
||||||
@ -197,11 +196,10 @@ bool Rover::verify_command(const AP_Mission::Mission_Command& cmd)
|
|||||||
|
|
||||||
default:
|
default:
|
||||||
// error message
|
// error message
|
||||||
gcs_send_text_fmt(MAV_SEVERITY_WARNING,"Skipping invalid cmd #%i",cmd.id);
|
gcs_send_text_fmt(MAV_SEVERITY_WARNING, "Skipping invalid cmd #%i", cmd.id);
|
||||||
// return true if we do not recognize the command so that we move on to the next command
|
// return true if we do not recognize the command so that we move on to the next command
|
||||||
return true;
|
return true;
|
||||||
}
|
}
|
||||||
|
|
||||||
}
|
}
|
||||||
|
|
||||||
/********************************************************************************/
|
/********************************************************************************/
|
||||||
@ -211,7 +209,7 @@ bool Rover::verify_command(const AP_Mission::Mission_Command& cmd)
|
|||||||
void Rover::do_RTL(void)
|
void Rover::do_RTL(void)
|
||||||
{
|
{
|
||||||
prev_WP = current_loc;
|
prev_WP = current_loc;
|
||||||
control_mode = RTL;
|
control_mode = RTL;
|
||||||
next_WP = home;
|
next_WP = home;
|
||||||
}
|
}
|
||||||
|
|
||||||
@ -238,7 +236,7 @@ void Rover::do_loiter_unlimited(const AP_Mission::Mission_Command& cmd)
|
|||||||
{
|
{
|
||||||
active_loiter = true;
|
active_loiter = true;
|
||||||
do_nav_wp(cmd);
|
do_nav_wp(cmd);
|
||||||
loiter_duration = 100; // an arbitrary large loiter time
|
loiter_duration = 100; // an arbitrary large loiter time
|
||||||
}
|
}
|
||||||
|
|
||||||
// do_loiter_time - initiate loitering at a point for a given time period
|
// do_loiter_time - initiate loitering at a point for a given time period
|
||||||
@ -331,7 +329,7 @@ bool Rover::verify_nav_wp(const AP_Mission::Mission_Command& cmd)
|
|||||||
bool Rover::verify_RTL()
|
bool Rover::verify_RTL()
|
||||||
{
|
{
|
||||||
if (wp_distance <= g.waypoint_radius) {
|
if (wp_distance <= g.waypoint_radius) {
|
||||||
gcs_send_text(MAV_SEVERITY_INFO,"Reached destination");
|
gcs_send_text(MAV_SEVERITY_INFO, "Reached destination");
|
||||||
rtl_complete = true;
|
rtl_complete = true;
|
||||||
return true;
|
return true;
|
||||||
}
|
}
|
||||||
@ -413,7 +411,7 @@ void Rover::do_within_distance(const AP_Mission::Mission_Command& cmd)
|
|||||||
bool Rover::verify_wait_delay()
|
bool Rover::verify_wait_delay()
|
||||||
{
|
{
|
||||||
if ((uint32_t)(millis() - condition_start) > (uint32_t)condition_value) {
|
if ((uint32_t)(millis() - condition_start) > (uint32_t)condition_value) {
|
||||||
condition_value = 0;
|
condition_value = 0;
|
||||||
return true;
|
return true;
|
||||||
}
|
}
|
||||||
return false;
|
return false;
|
||||||
|
Loading…
Reference in New Issue
Block a user