mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-21 07:13:56 -04:00
SITL: avoid use of stderr/::fprintf
This commit is contained in:
parent
94ad32b91c
commit
c9df857f16
@ -37,6 +37,10 @@ Protocol:
|
|||||||
- in the case that we don't have ESC telemetry, consider probing ESCs periodically with an "OK"-request while disarmed
|
- in the case that we don't have ESC telemetry, consider probing ESCs periodically with an "OK"-request while disarmed
|
||||||
*/
|
*/
|
||||||
|
|
||||||
|
#include <AP_HAL/AP_HAL.h>
|
||||||
|
|
||||||
|
extern const AP_HAL::HAL& hal;
|
||||||
|
|
||||||
#include <AP_Math/AP_Math.h>
|
#include <AP_Math/AP_Math.h>
|
||||||
|
|
||||||
#include "SIM_FETtecOneWireESC.h"
|
#include "SIM_FETtecOneWireESC.h"
|
||||||
@ -227,7 +231,7 @@ void FETtecOneWireESC::running_handle_config_message(FETtecOneWireESC::ESC &esc)
|
|||||||
case ConfigMessageType::NOT_OK:
|
case ConfigMessageType::NOT_OK:
|
||||||
break;
|
break;
|
||||||
case ConfigMessageType::BL_START_FW: // BL only
|
case ConfigMessageType::BL_START_FW: // BL only
|
||||||
::fprintf(stderr, "received unexpected BL_START_FW message\n");
|
hal.console->printf("received unexpected BL_START_FW message\n");
|
||||||
AP_HAL::panic("received unexpected BL_START_FW message");
|
AP_HAL::panic("received unexpected BL_START_FW message");
|
||||||
return;
|
return;
|
||||||
case ConfigMessageType::BL_PAGES_TO_FLASH: // BL only
|
case ConfigMessageType::BL_PAGES_TO_FLASH: // BL only
|
||||||
|
@ -18,7 +18,9 @@
|
|||||||
|
|
||||||
#include "SIM_Frsky_D.h"
|
#include "SIM_Frsky_D.h"
|
||||||
|
|
||||||
#include <stdio.h>
|
#include <AP_HAL/AP_HAL.h>
|
||||||
|
|
||||||
|
extern const AP_HAL::HAL& hal;
|
||||||
|
|
||||||
using namespace SITL;
|
using namespace SITL;
|
||||||
|
|
||||||
@ -30,7 +32,7 @@ static const uint8_t BYTESTUFF_D = 0x5D;
|
|||||||
|
|
||||||
void Frsky_D::handle_data(uint8_t id, uint16_t data)
|
void Frsky_D::handle_data(uint8_t id, uint16_t data)
|
||||||
{
|
{
|
||||||
::fprintf(stderr,
|
hal.console->printf(
|
||||||
"Frsky: id=%s (0x%02X) data=%u\n",
|
"Frsky: id=%s (0x%02X) data=%u\n",
|
||||||
dataid_string((DataID)id),
|
dataid_string((DataID)id),
|
||||||
(unsigned)_id,
|
(unsigned)_id,
|
||||||
|
@ -21,6 +21,8 @@
|
|||||||
#include <stdio.h>
|
#include <stdio.h>
|
||||||
#include <AP_Math/AP_Math.h>
|
#include <AP_Math/AP_Math.h>
|
||||||
|
|
||||||
|
extern const AP_HAL::HAL& hal;
|
||||||
|
|
||||||
using namespace SITL;
|
using namespace SITL;
|
||||||
|
|
||||||
// table of user settable parameters
|
// table of user settable parameters
|
||||||
@ -81,9 +83,9 @@ void Gripper_EPM::update_from_demand()
|
|||||||
}
|
}
|
||||||
|
|
||||||
if (should_report()) {
|
if (should_report()) {
|
||||||
::fprintf(stderr, "demand=%f\n", demand);
|
hal.console->printf("demand=%f\n", demand);
|
||||||
printf("Field strength: %f%%\n", field_strength);
|
hal.console->printf("Field strength: %f%%\n", field_strength);
|
||||||
printf("Field strength: %f Tesla\n", tesla());
|
hal.console->printf("Field strength: %f Tesla\n", tesla());
|
||||||
last_report_us = now;
|
last_report_us = now;
|
||||||
reported_field_strength = field_strength;
|
reported_field_strength = field_strength;
|
||||||
}
|
}
|
||||||
|
@ -21,6 +21,8 @@
|
|||||||
#include "AP_Math/AP_Math.h"
|
#include "AP_Math/AP_Math.h"
|
||||||
#include <stdio.h>
|
#include <stdio.h>
|
||||||
|
|
||||||
|
extern const AP_HAL::HAL& hal;
|
||||||
|
|
||||||
using namespace SITL;
|
using namespace SITL;
|
||||||
|
|
||||||
// table of user settable parameters
|
// table of user settable parameters
|
||||||
@ -96,7 +98,7 @@ void Gripper_Servo::update(const struct sitl_input &input)
|
|||||||
jaw_gap = gap * (1.0f - position);
|
jaw_gap = gap * (1.0f - position);
|
||||||
}
|
}
|
||||||
if (should_report()) {
|
if (should_report()) {
|
||||||
::fprintf(stderr, "position_demand=%f jaw_gap=%f load=%f\n", position_demand, jaw_gap, load_mass);
|
hal.console->printf("position_demand=%f jaw_gap=%f load=%f\n", position_demand, jaw_gap, load_mass);
|
||||||
last_report_us = now;
|
last_report_us = now;
|
||||||
reported_position = position;
|
reported_position = position;
|
||||||
}
|
}
|
||||||
|
@ -6,6 +6,9 @@
|
|||||||
|
|
||||||
using namespace SITL;
|
using namespace SITL;
|
||||||
|
|
||||||
|
#include <AP_HAL/AP_HAL.h>
|
||||||
|
extern const AP_HAL::HAL& hal;
|
||||||
|
|
||||||
MS5XXX::MS5XXX() :
|
MS5XXX::MS5XXX() :
|
||||||
I2CDevice()
|
I2CDevice()
|
||||||
{
|
{
|
||||||
@ -163,7 +166,7 @@ int MS5XXX::rdwr(I2C::i2c_rdwr_ioctl_data *&data)
|
|||||||
cmd == Command::RESET) {
|
cmd == Command::RESET) {
|
||||||
// this is OK - RESET is OK in UNINITIALISED
|
// this is OK - RESET is OK in UNINITIALISED
|
||||||
} else {
|
} else {
|
||||||
::fprintf(stderr, "Command (0x%02x) received while not running (state=%u)\n", (unsigned)cmd, (unsigned)state);
|
hal.console->printf("Command (0x%02x) received while not running (state=%u)\n", (unsigned)cmd, (unsigned)state);
|
||||||
return -1; // we could die instead...
|
return -1; // we could die instead...
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
@ -199,7 +202,7 @@ int MS5XXX::rdwr(I2C::i2c_rdwr_ioctl_data *&data)
|
|||||||
if (data->msgs[1].len == 0) {
|
if (data->msgs[1].len == 0) {
|
||||||
// upon not getting a reading back the driver commands a
|
// upon not getting a reading back the driver commands a
|
||||||
// conversion-read but doesn't wait for a response!
|
// conversion-read but doesn't wait for a response!
|
||||||
::fprintf(stderr, "read of length zero\n");
|
hal.console->printf("read of length zero\n");
|
||||||
return -1;
|
return -1;
|
||||||
}
|
}
|
||||||
if (data->msgs[1].len != 3) {
|
if (data->msgs[1].len != 3) {
|
||||||
|
@ -24,6 +24,8 @@
|
|||||||
#include <unistd.h>
|
#include <unistd.h>
|
||||||
#include <fcntl.h>
|
#include <fcntl.h>
|
||||||
|
|
||||||
|
extern const AP_HAL::HAL& hal;
|
||||||
|
|
||||||
using namespace SITL;
|
using namespace SITL;
|
||||||
|
|
||||||
Vicon::Vicon() :
|
Vicon::Vicon() :
|
||||||
@ -89,7 +91,7 @@ void Vicon::update_vicon_position_estimate(const Location &loc,
|
|||||||
uint16_t buf_len = mavlink_msg_to_send_buffer(buf, &msg_buf[i].obs_msg);
|
uint16_t buf_len = mavlink_msg_to_send_buffer(buf, &msg_buf[i].obs_msg);
|
||||||
|
|
||||||
if (::write(fd_my_end, (void*)&buf, buf_len) != buf_len) {
|
if (::write(fd_my_end, (void*)&buf, buf_len) != buf_len) {
|
||||||
::fprintf(stderr, "Vicon: write failure\n");
|
hal.console->printf("Vicon: write failure\n");
|
||||||
}
|
}
|
||||||
msg_buf[i].time_send_us = 0;
|
msg_buf[i].time_send_us = 0;
|
||||||
}
|
}
|
||||||
|
Loading…
Reference in New Issue
Block a user