mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-10 18:08:30 -04:00
added send_text_P()
this merges the send_text_P() updates from APM git-svn-id: https://arducopter.googlecode.com/svn/trunk@1788 f9c3cf11-9bcb-44bc-f272-b75c42450872
This commit is contained in:
parent
8ca4986375
commit
f0458631a3
@ -65,6 +65,13 @@ public:
|
||||
///
|
||||
void send_text(uint8_t severity, const char *str) {}
|
||||
|
||||
/// Send a text message with a PSTR()
|
||||
///
|
||||
/// @param severity A value describing the importance of the message.
|
||||
/// @param str The text to be sent.
|
||||
///
|
||||
void send_text_P(uint8_t severity, const char *str) {}
|
||||
|
||||
/// Send acknowledgement for a message.
|
||||
///
|
||||
/// @param id The message ID being acknowledged.
|
||||
@ -133,6 +140,7 @@ public:
|
||||
void init(BetterStream *port);
|
||||
void send_message(uint8_t id, uint32_t param = 0);
|
||||
void send_text(uint8_t severity, const char *str);
|
||||
void send_text_P(uint8_t severity, const char *str);
|
||||
void acknowledge(uint8_t id, uint8_t sum1, uint8_t sum2);
|
||||
void data_stream_send(uint16_t freqMin, uint16_t freqMax);
|
||||
private:
|
||||
|
@ -53,13 +53,13 @@ GCS_MAVLINK::update(void)
|
||||
|
||||
// stop waypoint sending if timeout
|
||||
if (global_data.waypoint_sending && (millis() - global_data.waypoint_timelast_send) > global_data.waypoint_send_timeout){
|
||||
send_text(SEVERITY_LOW,PSTR("waypoint send timeout"));
|
||||
send_text_P(SEVERITY_LOW,PSTR("waypoint send timeout"));
|
||||
global_data.waypoint_sending = false;
|
||||
}
|
||||
|
||||
// stop waypoint receiving if timeout
|
||||
if (global_data.waypoint_receiving && (millis() - global_data.waypoint_timelast_receive) > global_data.waypoint_receive_timeout){
|
||||
send_text(SEVERITY_LOW,PSTR("waypoint receive timeout"));
|
||||
send_text_P(SEVERITY_LOW,PSTR("waypoint receive timeout"));
|
||||
global_data.waypoint_receiving = false;
|
||||
}
|
||||
}
|
||||
@ -116,6 +116,18 @@ GCS_MAVLINK::send_text(uint8_t severity, const char *str)
|
||||
mavlink_send_text(chan,severity,str);
|
||||
}
|
||||
|
||||
void
|
||||
GCS_MAVLINK::send_text_P(uint8_t severity, const char *str)
|
||||
{
|
||||
mavlink_statustext_t m;
|
||||
uint8_t i;
|
||||
for (i=0; i<sizeof(m.text); i++) {
|
||||
m.text[i] = pgm_read_byte(str++);
|
||||
}
|
||||
if (i < sizeof(m.text)) m.text[i] = 0;
|
||||
mavlink_send_text(chan, severity, (const char *)m.text);
|
||||
}
|
||||
|
||||
void
|
||||
GCS_MAVLINK::acknowledge(uint8_t id, uint8_t sum1, uint8_t sum2)
|
||||
{
|
||||
@ -193,7 +205,7 @@ void GCS_MAVLINK::handleMessage(mavlink_message_t* msg)
|
||||
if (mavlink_check_target(packet.target,packet.target_component)) break;
|
||||
|
||||
// do action
|
||||
send_text(SEVERITY_LOW,PSTR("action received"));
|
||||
send_text_P(SEVERITY_LOW,PSTR("action received"));
|
||||
switch(packet.action){
|
||||
|
||||
case MAV_ACTION_LAUNCH:
|
||||
@ -286,7 +298,7 @@ void GCS_MAVLINK::handleMessage(mavlink_message_t* msg)
|
||||
|
||||
case MAVLINK_MSG_ID_WAYPOINT_REQUEST_LIST:
|
||||
{
|
||||
//send_text(SEVERITY_LOW,PSTR("waypoint request list"));
|
||||
//send_text_P(SEVERITY_LOW,PSTR("waypoint request list"));
|
||||
|
||||
// decode
|
||||
mavlink_waypoint_request_list_t packet;
|
||||
@ -312,7 +324,7 @@ void GCS_MAVLINK::handleMessage(mavlink_message_t* msg)
|
||||
|
||||
case MAVLINK_MSG_ID_WAYPOINT_REQUEST:
|
||||
{
|
||||
//send_text(SEVERITY_LOW,PSTR("waypoint request"));
|
||||
//send_text_P(SEVERITY_LOW,PSTR("waypoint request"));
|
||||
|
||||
// Check if sending waypiont
|
||||
if (!global_data.waypoint_sending) break;
|
||||
@ -392,7 +404,7 @@ void GCS_MAVLINK::handleMessage(mavlink_message_t* msg)
|
||||
|
||||
case MAVLINK_MSG_ID_WAYPOINT_ACK:
|
||||
{
|
||||
//send_text(SEVERITY_LOW,PSTR("waypoint ack"));
|
||||
//send_text_P(SEVERITY_LOW,PSTR("waypoint ack"));
|
||||
|
||||
// decode
|
||||
mavlink_waypoint_ack_t packet;
|
||||
@ -409,7 +421,7 @@ void GCS_MAVLINK::handleMessage(mavlink_message_t* msg)
|
||||
|
||||
case MAVLINK_MSG_ID_PARAM_REQUEST_LIST:
|
||||
{
|
||||
//send_text(SEVERITY_LOW,PSTR("param request list"));
|
||||
//send_text_P(SEVERITY_LOW,PSTR("param request list"));
|
||||
|
||||
// decode
|
||||
mavlink_param_request_list_t packet;
|
||||
@ -425,7 +437,7 @@ void GCS_MAVLINK::handleMessage(mavlink_message_t* msg)
|
||||
|
||||
case MAVLINK_MSG_ID_WAYPOINT_CLEAR_ALL:
|
||||
{
|
||||
//send_text(SEVERITY_LOW,PSTR("waypoint clear all"));
|
||||
//send_text_P(SEVERITY_LOW,PSTR("waypoint clear all"));
|
||||
|
||||
// decode
|
||||
mavlink_waypoint_clear_all_t packet;
|
||||
@ -444,7 +456,7 @@ void GCS_MAVLINK::handleMessage(mavlink_message_t* msg)
|
||||
|
||||
case MAVLINK_MSG_ID_WAYPOINT_SET_CURRENT:
|
||||
{
|
||||
//send_text(SEVERITY_LOW,PSTR("waypoint set current"));
|
||||
//send_text_P(SEVERITY_LOW,PSTR("waypoint set current"));
|
||||
|
||||
// decode
|
||||
mavlink_waypoint_set_current_t packet;
|
||||
@ -466,7 +478,7 @@ void GCS_MAVLINK::handleMessage(mavlink_message_t* msg)
|
||||
|
||||
case MAVLINK_MSG_ID_WAYPOINT_COUNT:
|
||||
{
|
||||
//send_text(SEVERITY_LOW,PSTR("waypoint count"));
|
||||
//send_text_P(SEVERITY_LOW,PSTR("waypoint count"));
|
||||
|
||||
// decode
|
||||
mavlink_waypoint_count_t packet;
|
||||
@ -587,7 +599,7 @@ void GCS_MAVLINK::handleMessage(mavlink_message_t* msg)
|
||||
msg->compid,
|
||||
type);
|
||||
|
||||
send_text(SEVERITY_LOW,PSTR("flight plan received"));
|
||||
send_text_P(SEVERITY_LOW,PSTR("flight plan received"));
|
||||
global_data.waypoint_receiving = false;
|
||||
// XXX ignores waypoint radius for individual waypoints, can
|
||||
// only set WP_RADIUS parameter
|
||||
|
@ -66,6 +66,13 @@ public:
|
||||
///
|
||||
void send_text(uint8_t severity, const char *str) {}
|
||||
|
||||
/// Send a text message with a PSTR()
|
||||
///
|
||||
/// @param severity A value describing the importance of the message.
|
||||
/// @param str The text to be sent.
|
||||
///
|
||||
void send_text_P(uint8_t severity, const char *str) {}
|
||||
|
||||
/// Send acknowledgement for a message.
|
||||
///
|
||||
/// @param id The message ID being acknowledged.
|
||||
@ -107,6 +114,7 @@ public:
|
||||
void init(BetterStream *port);
|
||||
void send_message(uint8_t id, uint32_t param = 0);
|
||||
void send_text(uint8_t severity, const char *str);
|
||||
void send_text_P(uint8_t severity, const char *str);
|
||||
void acknowledge(uint8_t id, uint8_t sum1, uint8_t sum2);
|
||||
private:
|
||||
void output_HIL();
|
||||
|
@ -118,6 +118,11 @@ HIL_XPLANE::send_text(uint8_t severity, const char *str)
|
||||
{
|
||||
}
|
||||
|
||||
void
|
||||
HIL_XPLANE::send_text_P(uint8_t severity, const char *str)
|
||||
{
|
||||
}
|
||||
|
||||
void
|
||||
HIL_XPLANE::acknowledge(uint8_t id, uint8_t sum1, uint8_t sum2)
|
||||
{
|
||||
|
@ -253,7 +253,7 @@ void start_new_log(byte num_existing_logs)
|
||||
DataFlash.FinishWrite();
|
||||
DataFlash.StartWrite(start_pages[num_existing_logs-1]);
|
||||
}else{
|
||||
gcs.send_text(SEVERITY_LOW,"<start_new_log> Logs full - logging discontinued");
|
||||
gcs.send_text_P(SEVERITY_LOW,PSTR("<start_new_log> Logs full - logging discontinued"));
|
||||
}
|
||||
}
|
||||
|
||||
|
@ -16,7 +16,7 @@ static uint8_t mavlink_check_target(uint8_t sysid, uint8_t compid)
|
||||
return 1;
|
||||
|
||||
}else if(compid != mavlink_system.compid){
|
||||
gcs.send_text(SEVERITY_LOW,"component id mismatch");
|
||||
gcs.send_text_P(SEVERITY_LOW,PSTR("component id mismatch"));
|
||||
return 0; // XXX currently not receiving correct compid from gcs
|
||||
|
||||
}else{
|
||||
|
@ -133,7 +133,7 @@ It looks to see what the next command type is and finds the last command.
|
||||
*/
|
||||
void set_next_WP(struct Location *wp)
|
||||
{
|
||||
//GCS.send_text(SEVERITY_LOW,"load WP");
|
||||
//GCS.send_text_P(SEVERITY_LOW,PSTR("load WP"));
|
||||
SendDebug("MSG <set_next_wp> wp_index: ");
|
||||
SendDebugln(g.waypoint_index, DEC);
|
||||
gcs.send_message(MSG_COMMAND_LIST, g.waypoint_index);
|
||||
|
@ -153,7 +153,7 @@ bool verify_must()
|
||||
break;
|
||||
|
||||
default:
|
||||
//gcs.send_text(SEVERITY_HIGH,"<verify_must: default> No current Must commands");
|
||||
//gcs.send_text_P(SEVERITY_HIGH,PSTR("<verify_must: default> No current Must commands"));
|
||||
return false;
|
||||
break;
|
||||
}
|
||||
@ -180,7 +180,7 @@ bool verify_may()
|
||||
break;
|
||||
|
||||
default:
|
||||
//gcs.send_text(SEVERITY_HIGH,"<verify_must: default> No current May commands");
|
||||
//gcs.send_text_P(SEVERITY_HIGH,PSTR("<verify_must: default> No current May commands"));
|
||||
return false;
|
||||
break;
|
||||
}
|
||||
@ -297,7 +297,7 @@ bool verify_nav_wp()
|
||||
|
||||
// Have we passed the WP?
|
||||
if(loiter_sum > 90){
|
||||
gcs.send_text(SEVERITY_MEDIUM,"Missed WP");
|
||||
gcs.send_text_P(SEVERITY_MEDIUM,PSTR("Missed WP"));
|
||||
return true;
|
||||
}
|
||||
return false;
|
||||
@ -311,7 +311,7 @@ bool verify_loiter_unlim()
|
||||
bool verify_loiter_time()
|
||||
{
|
||||
if ((millis() - loiter_time) > (long)loiter_time_max * 10000l) { // scale loiter_time_max from (sec*10) to milliseconds
|
||||
gcs.send_text(SEVERITY_LOW,"<verify_must: MAV_CMD_NAV_LOITER_TIME> LOITER time complete ");
|
||||
gcs.send_text_P(SEVERITY_LOW,PSTR("verify_must: LOITER time complete"));
|
||||
return true;
|
||||
}
|
||||
return false;
|
||||
@ -320,7 +320,7 @@ bool verify_loiter_time()
|
||||
bool verify_RTL()
|
||||
{
|
||||
if (wp_distance <= g.waypoint_radius) {
|
||||
gcs.send_text(SEVERITY_LOW,"Reached home");
|
||||
gcs.send_text_P(SEVERITY_LOW,PSTR("Reached home"));
|
||||
return true;
|
||||
}else{
|
||||
return false;
|
||||
@ -552,4 +552,4 @@ void do_repeat_relay()
|
||||
event_delay = next_command.lat * 500.0; // /2 (half cycle time) * 1000 (convert to milliseconds)
|
||||
event_repeat = next_command.alt * 2;
|
||||
update_events();
|
||||
}
|
||||
}
|
||||
|
@ -42,7 +42,7 @@ void load_next_command_from_EEPROM()
|
||||
// --------------------------------------------
|
||||
if(next_command.id == NO_COMMAND){
|
||||
// we are out of commands!
|
||||
gcs.send_text(SEVERITY_LOW,"out of commands!");
|
||||
gcs.send_text_P(SEVERITY_LOW,PSTR("out of commands!"));
|
||||
handle_no_commands();
|
||||
}
|
||||
}
|
||||
@ -100,7 +100,7 @@ void process_next_command()
|
||||
/**************************************************/
|
||||
void process_must()
|
||||
{
|
||||
gcs.send_text(SEVERITY_LOW,"New cmd: <process_must>");
|
||||
gcs.send_text_P(SEVERITY_LOW,PSTR("New cmd: <process_must>"));
|
||||
gcs.send_message(MSG_COMMAND_LIST, g.waypoint_index);
|
||||
|
||||
// clear May indexes
|
||||
@ -117,7 +117,7 @@ void process_must()
|
||||
|
||||
void process_may()
|
||||
{
|
||||
gcs.send_text(SEVERITY_LOW,"<process_may>");
|
||||
gcs.send_text_P(SEVERITY_LOW,PSTR("<process_may>"));
|
||||
gcs.send_message(MSG_COMMAND_LIST, g.waypoint_index);
|
||||
|
||||
command_may_ID = next_command.id;
|
||||
@ -136,7 +136,7 @@ void process_now()
|
||||
// -----------------------------------------
|
||||
next_command.id = NO_COMMAND;
|
||||
|
||||
gcs.send_text(SEVERITY_LOW, "<process_now>");
|
||||
gcs.send_text_P(SEVERITY_LOW, PSTR("<process_now>"));
|
||||
gcs.send_message(MSG_COMMAND_LIST, g.waypoint_index);
|
||||
}
|
||||
|
||||
|
@ -42,7 +42,7 @@ void failsafe_off_event()
|
||||
|
||||
void low_battery_event(void)
|
||||
{
|
||||
gcs.send_text(SEVERITY_HIGH,"Low Battery!");
|
||||
gcs.send_text_P(SEVERITY_HIGH,PSTR("Low Battery!"));
|
||||
set_mode(RTL);
|
||||
g.throttle_cruise.set(THROTTLE_CRUISE);
|
||||
}
|
||||
|
@ -21,7 +21,7 @@ void navigate()
|
||||
wp_distance = get_distance(¤t_loc, &next_WP);
|
||||
|
||||
if (wp_distance < 0){
|
||||
gcs.send_text(SEVERITY_HIGH,"<navigate> WP error - distance < 0");
|
||||
gcs.send_text_P(SEVERITY_HIGH,PSTR("<navigate> WP error - distance < 0"));
|
||||
//Serial.println(wp_distance,DEC);
|
||||
//print_current_waypoints();
|
||||
return;
|
||||
|
@ -215,10 +215,10 @@ void init_ardupilot()
|
||||
//********************************************************************************
|
||||
void startup_ground(void)
|
||||
{
|
||||
gcs.send_text(SEVERITY_LOW,"<startup_ground> GROUND START");
|
||||
gcs.send_text_P(SEVERITY_LOW,PSTR("<startup_ground> GROUND START"));
|
||||
|
||||
#if(GROUND_START_DELAY > 0)
|
||||
//gcs.send_text(SEVERITY_LOW," With Delay");
|
||||
//gcs.send_text_P(SEVERITY_LOW, PSTR(" With Delay"));
|
||||
delay(GROUND_START_DELAY * 1000);
|
||||
#endif
|
||||
|
||||
@ -255,7 +255,7 @@ void startup_ground(void)
|
||||
// -------------------
|
||||
init_commands();
|
||||
|
||||
gcs.send_text(SEVERITY_LOW,"\n\n Ready to FLY.");
|
||||
gcs.send_text_P(SEVERITY_LOW,PSTR("\n\n Ready to FLY."));
|
||||
}
|
||||
|
||||
void set_mode(byte mode)
|
||||
@ -274,7 +274,7 @@ void set_mode(byte mode)
|
||||
// disarm motors temp
|
||||
motor_auto_safe = false;
|
||||
}
|
||||
//send_text(SEVERITY_LOW,"control mode");
|
||||
//send_text_P(SEVERITY_LOW,PSTR("control mode"));
|
||||
//Serial.printf("set mode: %d old: %d\n", (int)mode, (int)control_mode);
|
||||
switch(control_mode)
|
||||
{
|
||||
|
Loading…
Reference in New Issue
Block a user