mirror of https://github.com/ArduPilot/ardupilot
Replace prog_char and prog_char_t with char
prog_char and prog_char_t are now the same as char on supported platforms. So, just change all places that use them and prefer char instead. AVR-specific places were not changed.
This commit is contained in:
parent
b52d1cfabb
commit
1b07dabeb7
|
@ -1426,7 +1426,7 @@ void Rover::gcs_update(void)
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
void Rover::gcs_send_text(MAV_SEVERITY severity, const prog_char_t *str)
|
void Rover::gcs_send_text(MAV_SEVERITY severity, const char *str)
|
||||||
{
|
{
|
||||||
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) {
|
||||||
|
@ -1443,7 +1443,7 @@ void Rover::gcs_send_text(MAV_SEVERITY severity, const prog_char_t *str)
|
||||||
* only one fits in the queue, so if you send more than one before the
|
* 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
|
* last one gets into the serial buffer then the old one will be lost
|
||||||
*/
|
*/
|
||||||
void Rover::gcs_send_text_fmt(const prog_char_t *fmt, ...)
|
void Rover::gcs_send_text_fmt(const char *fmt, ...)
|
||||||
{
|
{
|
||||||
va_list arg_list;
|
va_list arg_list;
|
||||||
gcs[0].pending_status.severity = (uint8_t)MAV_SEVERITY_WARNING;
|
gcs[0].pending_status.severity = (uint8_t)MAV_SEVERITY_WARNING;
|
||||||
|
|
|
@ -399,7 +399,7 @@ private:
|
||||||
void gcs_send_mission_item_reached_message(uint16_t mission_index);
|
void gcs_send_mission_item_reached_message(uint16_t mission_index);
|
||||||
void gcs_data_stream_send(void);
|
void gcs_data_stream_send(void);
|
||||||
void gcs_update(void);
|
void gcs_update(void);
|
||||||
void gcs_send_text(MAV_SEVERITY severity, const prog_char_t *str);
|
void gcs_send_text(MAV_SEVERITY severity, const char *str);
|
||||||
void gcs_retry_deferred(void);
|
void gcs_retry_deferred(void);
|
||||||
|
|
||||||
void do_erase_logs(void);
|
void do_erase_logs(void);
|
||||||
|
@ -490,7 +490,7 @@ private:
|
||||||
bool should_log(uint32_t mask);
|
bool should_log(uint32_t mask);
|
||||||
void frsky_telemetry_send(void);
|
void frsky_telemetry_send(void);
|
||||||
void print_hit_enter();
|
void print_hit_enter();
|
||||||
void gcs_send_text_fmt(const prog_char_t *fmt, ...);
|
void gcs_send_text_fmt(const char *fmt, ...);
|
||||||
void print_mode(AP_HAL::BetterStream *port, uint8_t mode);
|
void print_mode(AP_HAL::BetterStream *port, uint8_t mode);
|
||||||
bool start_command(const AP_Mission::Mission_Command& cmd);
|
bool start_command(const AP_Mission::Mission_Command& cmd);
|
||||||
bool verify_command(const AP_Mission::Mission_Command& cmd);
|
bool verify_command(const AP_Mission::Mission_Command& cmd);
|
||||||
|
|
|
@ -197,7 +197,7 @@ void Rover::init_ardupilot()
|
||||||
// menu; they must reset in order to fly.
|
// menu; they must reset in order to fly.
|
||||||
//
|
//
|
||||||
if (g.cli_enabled == 1) {
|
if (g.cli_enabled == 1) {
|
||||||
const prog_char_t *msg = "\nPress ENTER 3 times to start interactive setup\n";
|
const char *msg = "\nPress ENTER 3 times to start interactive setup\n";
|
||||||
cliSerial->println(msg);
|
cliSerial->println(msg);
|
||||||
if (gcs[1].initialised && (gcs[1].get_uart() != NULL)) {
|
if (gcs[1].initialised && (gcs[1].get_uart() != NULL)) {
|
||||||
gcs[1].get_uart()->println(msg);
|
gcs[1].get_uart()->println(msg);
|
||||||
|
|
|
@ -960,7 +960,7 @@ void Tracker::gcs_update(void)
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
void Tracker::gcs_send_text(MAV_SEVERITY severity, const prog_char_t *str)
|
void Tracker::gcs_send_text(MAV_SEVERITY severity, const char *str)
|
||||||
{
|
{
|
||||||
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) {
|
||||||
|
@ -977,7 +977,7 @@ void Tracker::gcs_send_text(MAV_SEVERITY severity, const prog_char_t *str)
|
||||||
* only one fits in the queue, so if you send more than one before the
|
* 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
|
* last one gets into the serial buffer then the old one will be lost
|
||||||
*/
|
*/
|
||||||
void Tracker::gcs_send_text_fmt(const prog_char_t *fmt, ...)
|
void Tracker::gcs_send_text_fmt(const char *fmt, ...)
|
||||||
{
|
{
|
||||||
va_list arg_list;
|
va_list arg_list;
|
||||||
gcs[0].pending_status.severity = (uint8_t)MAV_SEVERITY_WARNING;
|
gcs[0].pending_status.severity = (uint8_t)MAV_SEVERITY_WARNING;
|
||||||
|
|
|
@ -202,7 +202,7 @@ private:
|
||||||
void gcs_send_message(enum ap_message id);
|
void gcs_send_message(enum ap_message id);
|
||||||
void gcs_data_stream_send(void);
|
void gcs_data_stream_send(void);
|
||||||
void gcs_update(void);
|
void gcs_update(void);
|
||||||
void gcs_send_text(MAV_SEVERITY severity, const prog_char_t *str);
|
void gcs_send_text(MAV_SEVERITY severity, const char *str);
|
||||||
void gcs_retry_deferred(void);
|
void gcs_retry_deferred(void);
|
||||||
void load_parameters(void);
|
void load_parameters(void);
|
||||||
void update_auto(void);
|
void update_auto(void);
|
||||||
|
@ -245,7 +245,7 @@ private:
|
||||||
void tracking_update_pressure(const mavlink_scaled_pressure_t &msg);
|
void tracking_update_pressure(const mavlink_scaled_pressure_t &msg);
|
||||||
void tracking_manual_control(const mavlink_manual_control_t &msg);
|
void tracking_manual_control(const mavlink_manual_control_t &msg);
|
||||||
void update_armed_disarmed();
|
void update_armed_disarmed();
|
||||||
void gcs_send_text_fmt(const prog_char_t *fmt, ...);
|
void gcs_send_text_fmt(const char *fmt, ...);
|
||||||
void init_capabilities(void);
|
void init_capabilities(void);
|
||||||
void compass_cal_update();
|
void compass_cal_update();
|
||||||
|
|
||||||
|
|
|
@ -610,7 +610,7 @@ private:
|
||||||
void gcs_send_mission_item_reached_message(uint16_t mission_index);
|
void gcs_send_mission_item_reached_message(uint16_t mission_index);
|
||||||
void gcs_data_stream_send(void);
|
void gcs_data_stream_send(void);
|
||||||
void gcs_check_input(void);
|
void gcs_check_input(void);
|
||||||
void gcs_send_text(MAV_SEVERITY severity, const prog_char_t *str);
|
void gcs_send_text(MAV_SEVERITY severity, const char *str);
|
||||||
void do_erase_logs(void);
|
void do_erase_logs(void);
|
||||||
void Log_Write_AutoTune(uint8_t axis, uint8_t tune_step, float meas_target, float meas_min, float meas_max, float new_gain_rp, float new_gain_rd, float new_gain_sp, float new_ddt);
|
void Log_Write_AutoTune(uint8_t axis, uint8_t tune_step, float meas_target, float meas_min, float meas_max, float new_gain_rp, float new_gain_rd, float new_gain_sp, float new_ddt);
|
||||||
void Log_Write_AutoTuneDetails(float angle_cd, float rate_cds);
|
void Log_Write_AutoTuneDetails(float angle_cd, float rate_cds);
|
||||||
|
@ -934,7 +934,7 @@ private:
|
||||||
void takeoff_get_climb_rates(float& pilot_climb_rate, float& takeoff_climb_rate);
|
void takeoff_get_climb_rates(float& pilot_climb_rate, float& takeoff_climb_rate);
|
||||||
void print_hit_enter();
|
void print_hit_enter();
|
||||||
void tuning();
|
void tuning();
|
||||||
void gcs_send_text_fmt(const prog_char_t *fmt, ...);
|
void gcs_send_text_fmt(const char *fmt, ...);
|
||||||
bool start_command(const AP_Mission::Mission_Command& cmd);
|
bool start_command(const AP_Mission::Mission_Command& cmd);
|
||||||
bool verify_command(const AP_Mission::Mission_Command& cmd);
|
bool verify_command(const AP_Mission::Mission_Command& cmd);
|
||||||
bool verify_command_callback(const AP_Mission::Mission_Command& cmd);
|
bool verify_command_callback(const AP_Mission::Mission_Command& cmd);
|
||||||
|
|
|
@ -2030,7 +2030,7 @@ void Copter::gcs_check_input(void)
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
void Copter::gcs_send_text(MAV_SEVERITY severity, const prog_char_t *str)
|
void Copter::gcs_send_text(MAV_SEVERITY severity, const char *str)
|
||||||
{
|
{
|
||||||
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) {
|
||||||
|
@ -2044,7 +2044,7 @@ void Copter::gcs_send_text(MAV_SEVERITY severity, const prog_char_t *str)
|
||||||
* only one fits in the queue, so if you send more than one before the
|
* 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
|
* last one gets into the serial buffer then the old one will be lost
|
||||||
*/
|
*/
|
||||||
void Copter::gcs_send_text_fmt(const prog_char_t *fmt, ...)
|
void Copter::gcs_send_text_fmt(const char *fmt, ...)
|
||||||
{
|
{
|
||||||
va_list arg_list;
|
va_list arg_list;
|
||||||
gcs[0].pending_status.severity = (uint8_t)MAV_SEVERITY_WARNING;
|
gcs[0].pending_status.severity = (uint8_t)MAV_SEVERITY_WARNING;
|
||||||
|
|
|
@ -219,7 +219,7 @@ void Copter::init_ardupilot()
|
||||||
|
|
||||||
#if CLI_ENABLED == ENABLED
|
#if CLI_ENABLED == ENABLED
|
||||||
if (g.cli_enabled) {
|
if (g.cli_enabled) {
|
||||||
const prog_char_t *msg = "\nPress ENTER 3 times to start interactive setup\n";
|
const char *msg = "\nPress ENTER 3 times to start interactive setup\n";
|
||||||
cliSerial->println(msg);
|
cliSerial->println(msg);
|
||||||
if (gcs[1].initialised && (gcs[1].get_uart() != NULL)) {
|
if (gcs[1].initialised && (gcs[1].get_uart() != NULL)) {
|
||||||
gcs[1].get_uart()->println(msg);
|
gcs[1].get_uart()->println(msg);
|
||||||
|
|
|
@ -1992,7 +1992,7 @@ void Plane::gcs_update(void)
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
void Plane::gcs_send_text(MAV_SEVERITY severity, const prog_char_t *str)
|
void Plane::gcs_send_text(MAV_SEVERITY severity, const char *str)
|
||||||
{
|
{
|
||||||
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) {
|
||||||
|
@ -2009,7 +2009,7 @@ void Plane::gcs_send_text(MAV_SEVERITY severity, const prog_char_t *str)
|
||||||
* only one fits in the queue, so if you send more than one before the
|
* 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
|
* last one gets into the serial buffer then the old one will be lost
|
||||||
*/
|
*/
|
||||||
void Plane::gcs_send_text_fmt(const prog_char_t *fmt, ...)
|
void Plane::gcs_send_text_fmt(const char *fmt, ...)
|
||||||
{
|
{
|
||||||
va_list arg_list;
|
va_list arg_list;
|
||||||
gcs[0].pending_status.severity = (uint8_t)MAV_SEVERITY_WARNING;
|
gcs[0].pending_status.severity = (uint8_t)MAV_SEVERITY_WARNING;
|
||||||
|
|
|
@ -720,7 +720,7 @@ private:
|
||||||
void gcs_send_mission_item_reached_message(uint16_t mission_index);
|
void gcs_send_mission_item_reached_message(uint16_t mission_index);
|
||||||
void gcs_data_stream_send(void);
|
void gcs_data_stream_send(void);
|
||||||
void gcs_update(void);
|
void gcs_update(void);
|
||||||
void gcs_send_text(MAV_SEVERITY severity, const prog_char_t *str);
|
void gcs_send_text(MAV_SEVERITY severity, const char *str);
|
||||||
void gcs_send_airspeed_calibration(const Vector3f &vg);
|
void gcs_send_airspeed_calibration(const Vector3f &vg);
|
||||||
void gcs_retry_deferred(void);
|
void gcs_retry_deferred(void);
|
||||||
|
|
||||||
|
@ -917,7 +917,7 @@ private:
|
||||||
void update_aux();
|
void update_aux();
|
||||||
void update_is_flying_5Hz(void);
|
void update_is_flying_5Hz(void);
|
||||||
void crash_detection_update(void);
|
void crash_detection_update(void);
|
||||||
void gcs_send_text_fmt(const prog_char_t *fmt, ...);
|
void gcs_send_text_fmt(const char *fmt, ...);
|
||||||
void handle_auto_mode(void);
|
void handle_auto_mode(void);
|
||||||
void calc_throttle();
|
void calc_throttle();
|
||||||
void calc_nav_roll();
|
void calc_nav_roll();
|
||||||
|
|
|
@ -228,7 +228,7 @@ void Plane::init_ardupilot()
|
||||||
|
|
||||||
#if CLI_ENABLED == ENABLED
|
#if CLI_ENABLED == ENABLED
|
||||||
if (g.cli_enabled == 1) {
|
if (g.cli_enabled == 1) {
|
||||||
const prog_char_t *msg = "\nPress ENTER 3 times to start interactive setup\n";
|
const char *msg = "\nPress ENTER 3 times to start interactive setup\n";
|
||||||
cliSerial->println(msg);
|
cliSerial->println(msg);
|
||||||
if (gcs[1].initialised && (gcs[1].get_uart() != NULL)) {
|
if (gcs[1].initialised && (gcs[1].get_uart() != NULL)) {
|
||||||
gcs[1].get_uart()->println(msg);
|
gcs[1].get_uart()->println(msg);
|
||||||
|
|
|
@ -267,7 +267,7 @@ void AP_AutoTune::check_save(void)
|
||||||
/*
|
/*
|
||||||
log a parameter change from autotune
|
log a parameter change from autotune
|
||||||
*/
|
*/
|
||||||
void AP_AutoTune::log_param_change(float v, const prog_char_t *suffix)
|
void AP_AutoTune::log_param_change(float v, const char *suffix)
|
||||||
{
|
{
|
||||||
if (!dataflash.logging_started()) {
|
if (!dataflash.logging_started()) {
|
||||||
return;
|
return;
|
||||||
|
@ -288,7 +288,7 @@ void AP_AutoTune::log_param_change(float v, const prog_char_t *suffix)
|
||||||
set a float and save a float if it has changed by more than
|
set a float and save a float if it has changed by more than
|
||||||
0.1%. This reduces the number of insignificant EEPROM writes
|
0.1%. This reduces the number of insignificant EEPROM writes
|
||||||
*/
|
*/
|
||||||
void AP_AutoTune::save_float_if_changed(AP_Float &v, float value, const prog_char_t *suffix)
|
void AP_AutoTune::save_float_if_changed(AP_Float &v, float value, const char *suffix)
|
||||||
{
|
{
|
||||||
float old_value = v.get();
|
float old_value = v.get();
|
||||||
v.set(value);
|
v.set(value);
|
||||||
|
@ -301,7 +301,7 @@ void AP_AutoTune::save_float_if_changed(AP_Float &v, float value, const prog_cha
|
||||||
/*
|
/*
|
||||||
set a int16 and save if changed
|
set a int16 and save if changed
|
||||||
*/
|
*/
|
||||||
void AP_AutoTune::save_int16_if_changed(AP_Int16 &v, int16_t value, const prog_char_t *suffix)
|
void AP_AutoTune::save_int16_if_changed(AP_Int16 &v, int16_t value, const char *suffix)
|
||||||
{
|
{
|
||||||
int16_t old_value = v.get();
|
int16_t old_value = v.get();
|
||||||
v.set(value);
|
v.set(value);
|
||||||
|
|
|
@ -96,9 +96,9 @@ private:
|
||||||
void write_log_headers(void);
|
void write_log_headers(void);
|
||||||
void write_log(float servo, float demanded, float achieved);
|
void write_log(float servo, float demanded, float achieved);
|
||||||
|
|
||||||
void log_param_change(float v, const prog_char_t *suffix);
|
void log_param_change(float v, const char *suffix);
|
||||||
void save_float_if_changed(AP_Float &v, float value, const prog_char_t *suffix);
|
void save_float_if_changed(AP_Float &v, float value, const char *suffix);
|
||||||
void save_int16_if_changed(AP_Int16 &v, int16_t value, const prog_char_t *suffix);
|
void save_int16_if_changed(AP_Int16 &v, int16_t value, const char *suffix);
|
||||||
};
|
};
|
||||||
|
|
||||||
#endif // __AP_AUTOTUNE_H__
|
#endif // __AP_AUTOTUNE_H__
|
||||||
|
|
|
@ -204,7 +204,7 @@ AP_Declination::get_lookup_value(uint8_t x, uint8_t y)
|
||||||
for(i = start_index; i < (start_index + PGM_UINT8(&declination_keys[1][x])) && current_virtual_index <= y; i++) {
|
for(i = start_index; i < (start_index + PGM_UINT8(&declination_keys[1][x])) && current_virtual_index <= y; i++) {
|
||||||
|
|
||||||
// Pull out the row_value struct
|
// Pull out the row_value struct
|
||||||
memcpy((void*) &stval, (const prog_char *)&declination_values[i], sizeof(struct row_value));
|
memcpy((void*) &stval, (const char *)&declination_values[i], sizeof(struct row_value));
|
||||||
|
|
||||||
// Pull the first offset and determine sign
|
// Pull the first offset and determine sign
|
||||||
offset = stval.abs_offset;
|
offset = stval.abs_offset;
|
||||||
|
|
|
@ -145,14 +145,14 @@ const uint32_t AP_GPS::_baudrates[] = {4800U, 38400U, 115200U, 57600U, 9600U, 23
|
||||||
|
|
||||||
// initialisation blobs to send to the GPS to try to get it into the
|
// initialisation blobs to send to the GPS to try to get it into the
|
||||||
// right mode
|
// right mode
|
||||||
const prog_char AP_GPS::_initialisation_blob[] = UBLOX_SET_BINARY MTK_SET_BINARY SIRF_SET_BINARY;
|
const char AP_GPS::_initialisation_blob[] = UBLOX_SET_BINARY MTK_SET_BINARY SIRF_SET_BINARY;
|
||||||
const prog_char AP_GPS::_initialisation_raw_blob[] = UBLOX_SET_BINARY_RAW_BAUD MTK_SET_BINARY SIRF_SET_BINARY;
|
const char AP_GPS::_initialisation_raw_blob[] = UBLOX_SET_BINARY_RAW_BAUD MTK_SET_BINARY SIRF_SET_BINARY;
|
||||||
|
|
||||||
/*
|
/*
|
||||||
send some more initialisation string bytes if there is room in the
|
send some more initialisation string bytes if there is room in the
|
||||||
UART transmit buffer
|
UART transmit buffer
|
||||||
*/
|
*/
|
||||||
void AP_GPS::send_blob_start(uint8_t instance, const prog_char *_blob, uint16_t size)
|
void AP_GPS::send_blob_start(uint8_t instance, const char *_blob, uint16_t size)
|
||||||
{
|
{
|
||||||
initblob_state[instance].blob = _blob;
|
initblob_state[instance].blob = _blob;
|
||||||
initblob_state[instance].remaining = size;
|
initblob_state[instance].remaining = size;
|
||||||
|
|
|
@ -352,7 +352,7 @@ public:
|
||||||
AP_Int8 _gnss_mode;
|
AP_Int8 _gnss_mode;
|
||||||
|
|
||||||
// handle sending of initialisation strings to the GPS
|
// handle sending of initialisation strings to the GPS
|
||||||
void send_blob_start(uint8_t instance, const prog_char *_blob, uint16_t size);
|
void send_blob_start(uint8_t instance, const char *_blob, uint16_t size);
|
||||||
void send_blob_update(uint8_t instance);
|
void send_blob_update(uint8_t instance);
|
||||||
|
|
||||||
// lock out a GPS port, allowing another application to use the port
|
// lock out a GPS port, allowing another application to use the port
|
||||||
|
@ -413,13 +413,13 @@ private:
|
||||||
} detect_state[GPS_MAX_INSTANCES];
|
} detect_state[GPS_MAX_INSTANCES];
|
||||||
|
|
||||||
struct {
|
struct {
|
||||||
const prog_char *blob;
|
const char *blob;
|
||||||
uint16_t remaining;
|
uint16_t remaining;
|
||||||
} initblob_state[GPS_MAX_INSTANCES];
|
} initblob_state[GPS_MAX_INSTANCES];
|
||||||
|
|
||||||
static const uint32_t _baudrates[];
|
static const uint32_t _baudrates[];
|
||||||
static const prog_char _initialisation_blob[];
|
static const char _initialisation_blob[];
|
||||||
static const prog_char _initialisation_raw_blob[];
|
static const char _initialisation_raw_blob[];
|
||||||
|
|
||||||
void detect_instance(uint8_t instance);
|
void detect_instance(uint8_t instance);
|
||||||
void update_instance(uint8_t instance);
|
void update_instance(uint8_t instance);
|
||||||
|
|
|
@ -26,7 +26,7 @@
|
||||||
|
|
||||||
// initialisation blobs to send to the GPS to try to get it into the
|
// initialisation blobs to send to the GPS to try to get it into the
|
||||||
// right mode
|
// right mode
|
||||||
const prog_char AP_GPS_MTK::_initialisation_blob[] = MTK_OUTPUT_5HZ SBAS_ON WAAS_ON MTK_NAVTHRES_OFF;
|
const char AP_GPS_MTK::_initialisation_blob[] = MTK_OUTPUT_5HZ SBAS_ON WAAS_ON MTK_NAVTHRES_OFF;
|
||||||
|
|
||||||
AP_GPS_MTK::AP_GPS_MTK(AP_GPS &_gps, AP_GPS::GPS_State &_state, AP_HAL::UARTDriver *_port) :
|
AP_GPS_MTK::AP_GPS_MTK(AP_GPS &_gps, AP_GPS::GPS_State &_state, AP_HAL::UARTDriver *_port) :
|
||||||
AP_GPS_Backend(_gps, _state, _port),
|
AP_GPS_Backend(_gps, _state, _port),
|
||||||
|
|
|
@ -78,7 +78,7 @@ private:
|
||||||
// Buffer parse & GPS state update
|
// Buffer parse & GPS state update
|
||||||
void _parse_gps();
|
void _parse_gps();
|
||||||
|
|
||||||
static const prog_char _initialisation_blob[];
|
static const char _initialisation_blob[];
|
||||||
};
|
};
|
||||||
|
|
||||||
#endif // __AP_GPS_MTK_H__
|
#endif // __AP_GPS_MTK_H__
|
||||||
|
|
|
@ -90,7 +90,7 @@ extern const AP_HAL::HAL& hal;
|
||||||
"$PUBX,40,vtg,0,1,0,0,0,0*7F\r\n" /* VTG on at one per fix */ \
|
"$PUBX,40,vtg,0,1,0,0,0,0*7F\r\n" /* VTG on at one per fix */ \
|
||||||
"$PUBX,40,rmc,0,0,0,0,0,0*67\r\n" /* RMC off (XXX suppress other message types?) */
|
"$PUBX,40,rmc,0,0,0,0,0,0*67\r\n" /* RMC off (XXX suppress other message types?) */
|
||||||
|
|
||||||
const prog_char AP_GPS_NMEA::_initialisation_blob[] = SIRF_INIT_MSG MTK_INIT_MSG UBLOX_INIT_MSG;
|
const char AP_GPS_NMEA::_initialisation_blob[] = SIRF_INIT_MSG MTK_INIT_MSG UBLOX_INIT_MSG;
|
||||||
|
|
||||||
// NMEA message identifiers ////////////////////////////////////////////////////
|
// NMEA message identifiers ////////////////////////////////////////////////////
|
||||||
//
|
//
|
||||||
|
|
|
@ -148,19 +148,19 @@ private:
|
||||||
/// unit to send just the messages that we are interested
|
/// unit to send just the messages that we are interested
|
||||||
/// in using these strings
|
/// in using these strings
|
||||||
//@{
|
//@{
|
||||||
static const prog_char _SiRF_init_string[]; ///< init string for SiRF units
|
static const char _SiRF_init_string[]; ///< init string for SiRF units
|
||||||
static const prog_char _MTK_init_string[]; ///< init string for MediaTek units
|
static const char _MTK_init_string[]; ///< init string for MediaTek units
|
||||||
static const prog_char _ublox_init_string[]; ///< init string for ublox units
|
static const char _ublox_init_string[]; ///< init string for ublox units
|
||||||
//@}
|
//@}
|
||||||
|
|
||||||
/// @name GPS message identifier strings
|
/// @name GPS message identifier strings
|
||||||
//@{
|
//@{
|
||||||
static const prog_char _gprmc_string[];
|
static const char _gprmc_string[];
|
||||||
static const prog_char _gpgga_string[];
|
static const char _gpgga_string[];
|
||||||
static const prog_char _gpvtg_string[];
|
static const char _gpvtg_string[];
|
||||||
//@}
|
//@}
|
||||||
|
|
||||||
static const prog_char _initialisation_blob[];
|
static const char _initialisation_blob[];
|
||||||
};
|
};
|
||||||
|
|
||||||
#endif // __AP_GPS_NMEA_H__
|
#endif // __AP_GPS_NMEA_H__
|
||||||
|
|
|
@ -41,7 +41,7 @@ AP_GPS_SIRF::AP_GPS_SIRF(AP_GPS &_gps, AP_GPS::GPS_State &_state, AP_HAL::UARTDr
|
||||||
_payload_counter(0),
|
_payload_counter(0),
|
||||||
_msg_id(0)
|
_msg_id(0)
|
||||||
{
|
{
|
||||||
gps.send_blob_start(state.instance, (const prog_char *)_initialisation_blob, sizeof(_initialisation_blob));
|
gps.send_blob_start(state.instance, (const char *)_initialisation_blob, sizeof(_initialisation_blob));
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
||||||
|
|
|
@ -57,7 +57,7 @@ public:
|
||||||
virtual bool system_initializing() = 0;
|
virtual bool system_initializing() = 0;
|
||||||
virtual void system_initialized() = 0;
|
virtual void system_initialized() = 0;
|
||||||
|
|
||||||
virtual void panic(const prog_char_t *errormsg, ...) FORMAT(2, 3) NORETURN = 0;
|
virtual void panic(const char *errormsg, ...) FORMAT(2, 3) NORETURN = 0;
|
||||||
virtual void reboot(bool hold_in_bootloader) = 0;
|
virtual void reboot(bool hold_in_bootloader) = 0;
|
||||||
|
|
||||||
/**
|
/**
|
||||||
|
|
|
@ -25,14 +25,14 @@
|
||||||
all boards, although they can be overridden by a port
|
all boards, although they can be overridden by a port
|
||||||
*/
|
*/
|
||||||
|
|
||||||
void AP_HAL::UARTDriver::print_P(const prog_char_t *s)
|
void AP_HAL::UARTDriver::print_P(const char *s)
|
||||||
{
|
{
|
||||||
char c;
|
char c;
|
||||||
while ('\0' != (c = pgm_read_byte((const prog_char *)s++)))
|
while ('\0' != (c = pgm_read_byte((const char *)s++)))
|
||||||
write(c);
|
write(c);
|
||||||
}
|
}
|
||||||
|
|
||||||
void AP_HAL::UARTDriver::println_P(const prog_char_t *s)
|
void AP_HAL::UARTDriver::println_P(const char *s)
|
||||||
{
|
{
|
||||||
print_P(s);
|
print_P(s);
|
||||||
println();
|
println();
|
||||||
|
@ -51,7 +51,7 @@ void AP_HAL::UARTDriver::vprintf(const char *fmt, va_list ap)
|
||||||
print_vprintf((AP_HAL::Print*)this, 0, fmt, ap);
|
print_vprintf((AP_HAL::Print*)this, 0, fmt, ap);
|
||||||
}
|
}
|
||||||
|
|
||||||
void AP_HAL::UARTDriver::_printf_P(const prog_char *fmt, ...)
|
void AP_HAL::UARTDriver::_printf_P(const char *fmt, ...)
|
||||||
{
|
{
|
||||||
va_list ap;
|
va_list ap;
|
||||||
va_start(ap, fmt);
|
va_start(ap, fmt);
|
||||||
|
@ -59,7 +59,7 @@ void AP_HAL::UARTDriver::_printf_P(const prog_char *fmt, ...)
|
||||||
va_end(ap);
|
va_end(ap);
|
||||||
}
|
}
|
||||||
|
|
||||||
void AP_HAL::UARTDriver::vprintf_P(const prog_char *fmt, va_list ap)
|
void AP_HAL::UARTDriver::vprintf_P(const char *fmt, va_list ap)
|
||||||
{
|
{
|
||||||
print_vprintf((AP_HAL::Print*)this, 1, fmt, ap);
|
print_vprintf((AP_HAL::Print*)this, 1, fmt, ap);
|
||||||
}
|
}
|
||||||
|
|
|
@ -51,13 +51,13 @@ public:
|
||||||
* provided by AP_HAL to ensure consistency between ports to
|
* provided by AP_HAL to ensure consistency between ports to
|
||||||
* different boards
|
* different boards
|
||||||
*/
|
*/
|
||||||
void print_P(const prog_char_t *s);
|
void print_P(const char *s);
|
||||||
void println_P(const prog_char_t *s);
|
void println_P(const char *s);
|
||||||
void printf(const char *s, ...) FORMAT(2, 3);
|
void printf(const char *s, ...) FORMAT(2, 3);
|
||||||
void _printf_P(const prog_char *s, ...) FORMAT(2, 3);
|
void _printf_P(const char *s, ...) FORMAT(2, 3);
|
||||||
|
|
||||||
void vprintf(const char *s, va_list ap);
|
void vprintf(const char *s, va_list ap);
|
||||||
void vprintf_P(const prog_char *s, va_list ap);
|
void vprintf_P(const char *s, va_list ap);
|
||||||
};
|
};
|
||||||
|
|
||||||
#endif // __AP_HAL_UART_DRIVER_H__
|
#endif // __AP_HAL_UART_DRIVER_H__
|
||||||
|
|
|
@ -25,7 +25,7 @@
|
||||||
|
|
||||||
#include <AP_Common/AP_Common.h>
|
#include <AP_Common/AP_Common.h>
|
||||||
#include <AP_HAL/AP_HAL_Namespace.h>
|
#include <AP_HAL/AP_HAL_Namespace.h>
|
||||||
/* prog_char_t: */
|
/* char: */
|
||||||
#include <AP_Progmem/AP_Progmem.h>
|
#include <AP_Progmem/AP_Progmem.h>
|
||||||
|
|
||||||
#include "Stream.h"
|
#include "Stream.h"
|
||||||
|
@ -36,25 +36,22 @@
|
||||||
* on _vprintf().
|
* on _vprintf().
|
||||||
* Please provide your own platform-specic implementation of vprintf, sprintf,
|
* Please provide your own platform-specic implementation of vprintf, sprintf,
|
||||||
* etc. to implement the printf functions.
|
* etc. to implement the printf functions.
|
||||||
*
|
|
||||||
* TODO: Segregate prog_char_t dependent functions to be available on AVR
|
|
||||||
* platform only, with default implementations elsewhere.
|
|
||||||
*/
|
*/
|
||||||
|
|
||||||
class AP_HAL::BetterStream : public AP_HAL::Stream {
|
class AP_HAL::BetterStream : public AP_HAL::Stream {
|
||||||
public:
|
public:
|
||||||
BetterStream(void) {}
|
BetterStream(void) {}
|
||||||
|
|
||||||
virtual void print_P(const prog_char_t *) = 0;
|
virtual void print_P(const char *) = 0;
|
||||||
virtual void println_P(const prog_char_t *) = 0;
|
virtual void println_P(const char *) = 0;
|
||||||
virtual void printf(const char *, ...) FORMAT(2, 3) = 0;
|
virtual void printf(const char *, ...) FORMAT(2, 3) = 0;
|
||||||
/* No format checking on printf_P: can't currently support that on AVR */
|
/* No format checking on printf_P: can't currently support that on AVR */
|
||||||
virtual void _printf_P(const prog_char *, ...) = 0;
|
virtual void _printf_P(const char *, ...) = 0;
|
||||||
|
|
||||||
#define printf_P(fmt, ...) _printf_P((const prog_char *)fmt, ## __VA_ARGS__)
|
#define printf_P(fmt, ...) _printf_P((const char *)fmt, ## __VA_ARGS__)
|
||||||
|
|
||||||
virtual void vprintf(const char *, va_list) = 0;
|
virtual void vprintf(const char *, va_list) = 0;
|
||||||
virtual void vprintf_P(const prog_char *, va_list) = 0;
|
virtual void vprintf_P(const char *, va_list) = 0;
|
||||||
};
|
};
|
||||||
|
|
||||||
#endif // __AP_HAL_UTILITY_BETTERSTREAM_H__
|
#endif // __AP_HAL_UTILITY_BETTERSTREAM_H__
|
||||||
|
|
|
@ -33,7 +33,7 @@
|
||||||
#include "ftoa_engine.h"
|
#include "ftoa_engine.h"
|
||||||
#include <stdint.h>
|
#include <stdint.h>
|
||||||
|
|
||||||
#define PGM_INT8(addr) (int8_t)pgm_read_byte((const prog_char *)addr)
|
#define PGM_INT8(addr) (int8_t)pgm_read_byte((const char *)addr)
|
||||||
#define PGM_UINT32(addr) pgm_read_dword((const uint32_t *)addr)
|
#define PGM_UINT32(addr) pgm_read_dword((const uint32_t *)addr)
|
||||||
|
|
||||||
/*
|
/*
|
||||||
|
|
|
@ -223,10 +223,10 @@ void print_vprintf (AP_HAL::Print *s, unsigned char in_progmem, const char *fmt,
|
||||||
}
|
}
|
||||||
if (sign)
|
if (sign)
|
||||||
s->write(sign);
|
s->write(sign);
|
||||||
const prog_char_t *p = "inf";
|
const char *p = "inf";
|
||||||
if (vtype & FTOA_NAN)
|
if (vtype & FTOA_NAN)
|
||||||
p = "nan";
|
p = "nan";
|
||||||
while ( (ndigs = pgm_read_byte((const prog_char *)p)) != 0) {
|
while ( (ndigs = pgm_read_byte((const char *)p)) != 0) {
|
||||||
if (flags & FL_FLTUPP)
|
if (flags & FL_FLTUPP)
|
||||||
ndigs += 'I' - 'i';
|
ndigs += 'I' - 'i';
|
||||||
s->write(ndigs);
|
s->write(ndigs);
|
||||||
|
|
|
@ -71,7 +71,7 @@ bool EmptyScheduler::system_initializing() {
|
||||||
void EmptyScheduler::system_initialized()
|
void EmptyScheduler::system_initialized()
|
||||||
{}
|
{}
|
||||||
|
|
||||||
void EmptyScheduler::panic(const prog_char_t *errormsg, ...)
|
void EmptyScheduler::panic(const char *errormsg, ...)
|
||||||
{
|
{
|
||||||
va_list ap;
|
va_list ap;
|
||||||
|
|
||||||
|
|
|
@ -32,7 +32,7 @@ public:
|
||||||
bool system_initializing();
|
bool system_initializing();
|
||||||
void system_initialized();
|
void system_initialized();
|
||||||
|
|
||||||
void panic(const prog_char_t *errormsg, ...) FORMAT(2, 3) NORETURN;
|
void panic(const char *errormsg, ...) FORMAT(2, 3) NORETURN;
|
||||||
void reboot(bool hold_in_bootloader);
|
void reboot(bool hold_in_bootloader);
|
||||||
|
|
||||||
};
|
};
|
||||||
|
|
|
@ -230,7 +230,7 @@ void FLYMAPLEScheduler::system_initialized()
|
||||||
_initialized = true;
|
_initialized = true;
|
||||||
}
|
}
|
||||||
|
|
||||||
void FLYMAPLEScheduler::panic(const prog_char_t *errormsg, ...) {
|
void FLYMAPLEScheduler::panic(const char *errormsg, ...) {
|
||||||
/* Suspend timer processes. We still want the timer event to go off
|
/* Suspend timer processes. We still want the timer event to go off
|
||||||
* to run the _failsafe code, however. */
|
* to run the _failsafe code, however. */
|
||||||
// REVISIT: not tested on FLYMAPLE
|
// REVISIT: not tested on FLYMAPLE
|
||||||
|
|
|
@ -53,7 +53,7 @@ public:
|
||||||
bool system_initializing();
|
bool system_initializing();
|
||||||
void system_initialized();
|
void system_initialized();
|
||||||
|
|
||||||
void panic(const prog_char_t *errormsg, ...) FORMAT(2, 3) NORETURN;
|
void panic(const char *errormsg, ...) FORMAT(2, 3) NORETURN;
|
||||||
void reboot(bool hold_in_bootloader);
|
void reboot(bool hold_in_bootloader);
|
||||||
|
|
||||||
private:
|
private:
|
||||||
|
|
|
@ -407,7 +407,7 @@ void *Scheduler::_io_thread(void* arg)
|
||||||
return NULL;
|
return NULL;
|
||||||
}
|
}
|
||||||
|
|
||||||
void Scheduler::panic(const prog_char_t *errormsg, ...)
|
void Scheduler::panic(const char *errormsg, ...)
|
||||||
{
|
{
|
||||||
va_list ap;
|
va_list ap;
|
||||||
|
|
||||||
|
|
|
@ -43,7 +43,7 @@ public:
|
||||||
bool system_initializing();
|
bool system_initializing();
|
||||||
void system_initialized();
|
void system_initialized();
|
||||||
|
|
||||||
void panic(const prog_char_t *errormsg, ...) FORMAT(2, 3) NORETURN;
|
void panic(const char *errormsg, ...) FORMAT(2, 3) NORETURN;
|
||||||
void reboot(bool hold_in_bootloader);
|
void reboot(bool hold_in_bootloader);
|
||||||
|
|
||||||
void stop_clock(uint64_t time_usec);
|
void stop_clock(uint64_t time_usec);
|
||||||
|
|
|
@ -374,7 +374,7 @@ void *PX4Scheduler::_storage_thread(void)
|
||||||
return NULL;
|
return NULL;
|
||||||
}
|
}
|
||||||
|
|
||||||
void PX4Scheduler::panic(const prog_char_t *errormsg, ...)
|
void PX4Scheduler::panic(const char *errormsg, ...)
|
||||||
{
|
{
|
||||||
va_list ap;
|
va_list ap;
|
||||||
|
|
||||||
|
|
|
@ -60,7 +60,7 @@ public:
|
||||||
void suspend_timer_procs();
|
void suspend_timer_procs();
|
||||||
void resume_timer_procs();
|
void resume_timer_procs();
|
||||||
void reboot(bool hold_in_bootloader);
|
void reboot(bool hold_in_bootloader);
|
||||||
void panic(const prog_char_t *errormsg, ...) FORMAT(2, 3) NORETURN;
|
void panic(const char *errormsg, ...) FORMAT(2, 3) NORETURN;
|
||||||
|
|
||||||
bool in_timerprocess();
|
bool in_timerprocess();
|
||||||
bool system_initializing();
|
bool system_initializing();
|
||||||
|
|
|
@ -259,7 +259,7 @@ void SITLScheduler::_run_io_procs(bool called_from_isr)
|
||||||
_in_io_proc = false;
|
_in_io_proc = false;
|
||||||
}
|
}
|
||||||
|
|
||||||
void SITLScheduler::panic(const prog_char_t *errormsg, ...)
|
void SITLScheduler::panic(const char *errormsg, ...)
|
||||||
{
|
{
|
||||||
va_list ap;
|
va_list ap;
|
||||||
|
|
||||||
|
|
|
@ -41,7 +41,7 @@ public:
|
||||||
void system_initialized();
|
void system_initialized();
|
||||||
|
|
||||||
void reboot(bool hold_in_bootloader);
|
void reboot(bool hold_in_bootloader);
|
||||||
void panic(const prog_char_t *errormsg, ...) FORMAT(2, 3) NORETURN;
|
void panic(const char *errormsg, ...) FORMAT(2, 3) NORETURN;
|
||||||
|
|
||||||
bool interrupts_are_blocked(void) {
|
bool interrupts_are_blocked(void) {
|
||||||
return _nested_atomic_ctr != 0;
|
return _nested_atomic_ctr != 0;
|
||||||
|
|
|
@ -325,7 +325,7 @@ void *VRBRAINScheduler::_io_thread(void)
|
||||||
return NULL;
|
return NULL;
|
||||||
}
|
}
|
||||||
|
|
||||||
void VRBRAINScheduler::panic(const prog_char_t *errormsg, ...)
|
void VRBRAINScheduler::panic(const char *errormsg, ...)
|
||||||
{
|
{
|
||||||
va_list ap;
|
va_list ap;
|
||||||
|
|
||||||
|
|
|
@ -39,7 +39,7 @@ public:
|
||||||
void suspend_timer_procs();
|
void suspend_timer_procs();
|
||||||
void resume_timer_procs();
|
void resume_timer_procs();
|
||||||
void reboot(bool hold_in_bootloader);
|
void reboot(bool hold_in_bootloader);
|
||||||
void panic(const prog_char_t *errormsg, ...) FORMAT(2, 3) NORETURN;
|
void panic(const char *errormsg, ...) FORMAT(2, 3) NORETURN;
|
||||||
|
|
||||||
bool in_timerprocess();
|
bool in_timerprocess();
|
||||||
bool system_initializing();
|
bool system_initializing();
|
||||||
|
|
|
@ -593,7 +593,7 @@ bool AP_InertialSensor::calibrate_accel(AP_InertialSensor_UserInteract* interact
|
||||||
|
|
||||||
// capture data from 6 positions
|
// capture data from 6 positions
|
||||||
for (uint8_t i=0; i<6; i++) {
|
for (uint8_t i=0; i<6; i++) {
|
||||||
const prog_char_t *msg;
|
const char *msg;
|
||||||
|
|
||||||
// display message to user
|
// display message to user
|
||||||
switch ( i ) {
|
switch ( i ) {
|
||||||
|
|
|
@ -10,7 +10,7 @@
|
||||||
|
|
||||||
#include "AP_Limit_Module.h"
|
#include "AP_Limit_Module.h"
|
||||||
|
|
||||||
extern const prog_char_t *get_module_name(enum moduleid i) {
|
extern const char *get_module_name(enum moduleid i) {
|
||||||
|
|
||||||
switch (i) {
|
switch (i) {
|
||||||
case AP_LIMITS_GPSLOCK:
|
case AP_LIMITS_GPSLOCK:
|
||||||
|
|
|
@ -25,7 +25,7 @@ enum moduleid {
|
||||||
AP_LIMITS_ALTITUDE = (1 << 2)
|
AP_LIMITS_ALTITUDE = (1 << 2)
|
||||||
};
|
};
|
||||||
|
|
||||||
extern const prog_char_t *get_module_name(enum moduleid i);
|
extern const char *get_module_name(enum moduleid i);
|
||||||
|
|
||||||
// an integer type big enough to fit a bit field for all modules.
|
// an integer type big enough to fit a bit field for all modules.
|
||||||
// We have 3 modules, so 8-bit int is enough.
|
// We have 3 modules, so 8-bit int is enough.
|
||||||
|
|
|
@ -23,7 +23,7 @@ AP_HAL::BetterStream *Menu::_port;
|
||||||
|
|
||||||
|
|
||||||
// constructor
|
// constructor
|
||||||
Menu::Menu(const prog_char *prompt, const Menu::command *commands, uint8_t entries, preprompt ppfunc) :
|
Menu::Menu(const char *prompt, const Menu::command *commands, uint8_t entries, preprompt ppfunc) :
|
||||||
_prompt(prompt),
|
_prompt(prompt),
|
||||||
_commands(commands),
|
_commands(commands),
|
||||||
_entries(entries),
|
_entries(entries),
|
||||||
|
|
|
@ -126,7 +126,7 @@ private:
|
||||||
///
|
///
|
||||||
int8_t _call(uint8_t n, uint8_t argc);
|
int8_t _call(uint8_t n, uint8_t argc);
|
||||||
|
|
||||||
const prog_char * _prompt; ///< prompt to display
|
const char * _prompt; ///< prompt to display
|
||||||
const command * _commands; ///< array of commands
|
const command * _commands; ///< array of commands
|
||||||
const uint8_t _entries; ///< size of the menu
|
const uint8_t _entries; ///< size of the menu
|
||||||
const preprompt _ppfunc; ///< optional pre-prompt action
|
const preprompt _ppfunc; ///< optional pre-prompt action
|
||||||
|
|
|
@ -43,7 +43,7 @@ extern const AP_HAL::HAL &hal;
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
// some useful progmem macros
|
// some useful progmem macros
|
||||||
#define PGM_UINT8(addr) pgm_read_byte((const prog_char *)addr)
|
#define PGM_UINT8(addr) pgm_read_byte((const char *)addr)
|
||||||
#define PGM_UINT16(addr) pgm_read_word((const uint16_t *)addr)
|
#define PGM_UINT16(addr) pgm_read_word((const uint16_t *)addr)
|
||||||
#define PGM_FLOAT(addr) pgm_read_float((const float *)addr)
|
#define PGM_FLOAT(addr) pgm_read_float((const float *)addr)
|
||||||
#define PGM_POINTER(addr) pgm_read_pointer((const void *)addr)
|
#define PGM_POINTER(addr) pgm_read_pointer((const void *)addr)
|
||||||
|
|
|
@ -144,7 +144,7 @@ void DFMessageWriter_WriteSysInfo::process() {
|
||||||
_finished = true; // all done!
|
_finished = true; // all done!
|
||||||
}
|
}
|
||||||
|
|
||||||
// void DataFlash_Class::Log_Write_SysInfo(const prog_char_t *firmware_string)
|
// void DataFlash_Class::Log_Write_SysInfo(const char *firmware_string)
|
||||||
// {
|
// {
|
||||||
// DFMessageWriter_WriteSysInfo writer(firmware_string);
|
// DFMessageWriter_WriteSysInfo writer(firmware_string);
|
||||||
// writer->process();
|
// writer->process();
|
||||||
|
|
|
@ -24,7 +24,7 @@ protected:
|
||||||
class DFMessageWriter_WriteSysInfo : public DFMessageWriter {
|
class DFMessageWriter_WriteSysInfo : public DFMessageWriter {
|
||||||
public:
|
public:
|
||||||
DFMessageWriter_WriteSysInfo(DataFlash_Class &DataFlash,
|
DFMessageWriter_WriteSysInfo(DataFlash_Class &DataFlash,
|
||||||
const prog_char_t *firmware_string) :
|
const char *firmware_string) :
|
||||||
DFMessageWriter(DataFlash),
|
DFMessageWriter(DataFlash),
|
||||||
_firmware_string(firmware_string)
|
_firmware_string(firmware_string)
|
||||||
{ }
|
{ }
|
||||||
|
@ -41,7 +41,7 @@ private:
|
||||||
};
|
};
|
||||||
write_sysinfo_blockwriter_stage stage;
|
write_sysinfo_blockwriter_stage stage;
|
||||||
|
|
||||||
const prog_char_t *_firmware_string;
|
const char *_firmware_string;
|
||||||
};
|
};
|
||||||
|
|
||||||
class DFMessageWriter_WriteEntireMission : public DFMessageWriter {
|
class DFMessageWriter_WriteEntireMission : public DFMessageWriter {
|
||||||
|
@ -70,7 +70,7 @@ private:
|
||||||
class DFMessageWriter_DFLogStart : public DFMessageWriter {
|
class DFMessageWriter_DFLogStart : public DFMessageWriter {
|
||||||
public:
|
public:
|
||||||
DFMessageWriter_DFLogStart(DataFlash_Class &DataFlash,
|
DFMessageWriter_DFLogStart(DataFlash_Class &DataFlash,
|
||||||
const prog_char_t *firmware_string) :
|
const char *firmware_string) :
|
||||||
DFMessageWriter{DataFlash},
|
DFMessageWriter{DataFlash},
|
||||||
_writesysinfo(DataFlash, firmware_string),
|
_writesysinfo(DataFlash, firmware_string),
|
||||||
_writeentiremission(DataFlash)
|
_writeentiremission(DataFlash)
|
||||||
|
|
|
@ -38,7 +38,7 @@ class DataFlash_Class
|
||||||
public:
|
public:
|
||||||
FUNCTOR_TYPEDEF(print_mode_fn, void, AP_HAL::BetterStream*, uint8_t);
|
FUNCTOR_TYPEDEF(print_mode_fn, void, AP_HAL::BetterStream*, uint8_t);
|
||||||
FUNCTOR_TYPEDEF(vehicle_startup_message_Log_Writer, void);
|
FUNCTOR_TYPEDEF(vehicle_startup_message_Log_Writer, void);
|
||||||
DataFlash_Class(const prog_char_t *firmware_string) :
|
DataFlash_Class(const char *firmware_string) :
|
||||||
_startup_messagewriter(DFMessageWriter_DFLogStart(*this,firmware_string)),
|
_startup_messagewriter(DFMessageWriter_DFLogStart(*this,firmware_string)),
|
||||||
_vehicle_messages(NULL)
|
_vehicle_messages(NULL)
|
||||||
{ }
|
{ }
|
||||||
|
@ -85,7 +85,7 @@ public:
|
||||||
uint16_t StartNewLog(void);
|
uint16_t StartNewLog(void);
|
||||||
void AddLogFormats(const struct LogStructure *structures, uint8_t num_types);
|
void AddLogFormats(const struct LogStructure *structures, uint8_t num_types);
|
||||||
void EnableWrites(bool enable);
|
void EnableWrites(bool enable);
|
||||||
void Log_Write_SysInfo(const prog_char_t *firmware_string);
|
void Log_Write_SysInfo(const char *firmware_string);
|
||||||
bool Log_Write_Format(const struct LogStructure *structure);
|
bool Log_Write_Format(const struct LogStructure *structure);
|
||||||
bool Log_Write_Parameter(const char *name, float value);
|
bool Log_Write_Parameter(const char *name, float value);
|
||||||
void Log_Write_GPS(const AP_GPS &gps, uint8_t instance, int32_t relative_alt);
|
void Log_Write_GPS(const AP_GPS &gps, uint8_t instance, int32_t relative_alt);
|
||||||
|
|
|
@ -293,7 +293,7 @@ uint16_t DataFlash_Block::find_last_page_of_log(uint16_t log_number)
|
||||||
return -1;
|
return -1;
|
||||||
}
|
}
|
||||||
|
|
||||||
#define PGM_UINT8(addr) pgm_read_byte((const prog_char *)addr)
|
#define PGM_UINT8(addr) pgm_read_byte((const char *)addr)
|
||||||
|
|
||||||
#ifndef DATAFLASH_NO_CLI
|
#ifndef DATAFLASH_NO_CLI
|
||||||
/*
|
/*
|
||||||
|
@ -1014,7 +1014,7 @@ void DataFlash_Class::Log_Write_Vibration(const AP_InertialSensor &ins)
|
||||||
WriteBlock(&pkt, sizeof(pkt));
|
WriteBlock(&pkt, sizeof(pkt));
|
||||||
}
|
}
|
||||||
|
|
||||||
void DataFlash_Class::Log_Write_SysInfo(const prog_char_t *firmware_string)
|
void DataFlash_Class::Log_Write_SysInfo(const char *firmware_string)
|
||||||
{
|
{
|
||||||
Log_Write_Message(firmware_string);
|
Log_Write_Message(firmware_string);
|
||||||
|
|
||||||
|
@ -1060,7 +1060,6 @@ bool DataFlash_Class::Log_Write_Message(const char *message)
|
||||||
return WriteCriticalBlock(&pkt, sizeof(pkt));
|
return WriteCriticalBlock(&pkt, sizeof(pkt));
|
||||||
}
|
}
|
||||||
|
|
||||||
// Write a POWR packet
|
|
||||||
void DataFlash_Class::Log_Write_Power(void)
|
void DataFlash_Class::Log_Write_Power(void)
|
||||||
{
|
{
|
||||||
#if CONFIG_HAL_BOARD == HAL_BOARD_PX4
|
#if CONFIG_HAL_BOARD == HAL_BOARD_PX4
|
||||||
|
|
|
@ -164,7 +164,7 @@ public:
|
||||||
connections. This function is static so it can be called from
|
connections. This function is static so it can be called from
|
||||||
any library
|
any library
|
||||||
*/
|
*/
|
||||||
static void send_statustext_all(MAV_SEVERITY severity, const prog_char_t *fmt, ...);
|
static void send_statustext_all(MAV_SEVERITY severity, const char *fmt, ...);
|
||||||
|
|
||||||
/*
|
/*
|
||||||
send a MAVLink message to all components with this vehicle's system id
|
send a MAVLink message to all components with this vehicle's system id
|
||||||
|
|
|
@ -1172,7 +1172,7 @@ void GCS_MAVLINK::send_ahrs(AP_AHRS &ahrs)
|
||||||
/*
|
/*
|
||||||
send a statustext message to all active MAVLink connections
|
send a statustext message to all active MAVLink connections
|
||||||
*/
|
*/
|
||||||
void GCS_MAVLINK::send_statustext_all(MAV_SEVERITY severity, const prog_char_t *fmt, ...)
|
void GCS_MAVLINK::send_statustext_all(MAV_SEVERITY severity, const char *fmt, ...)
|
||||||
{
|
{
|
||||||
for (uint8_t i=0; i<MAVLINK_COMM_NUM_BUFFERS; i++) {
|
for (uint8_t i=0; i<MAVLINK_COMM_NUM_BUFFERS; i++) {
|
||||||
if ((1U<<i) & mavlink_active) {
|
if ((1U<<i) & mavlink_active) {
|
||||||
|
|
Loading…
Reference in New Issue