mirror of
https://github.com/PX4/PX4-Autopilot.git
synced 2026-05-21 13:02:25 +08:00
astyle shift module documentation to bottom of files
- Astyle chokes on the module description strings, so for now we can keep them near the bottom of each file.
This commit is contained in:
+60
-62
@@ -1531,6 +1531,65 @@ int DShotOutput::custom_command(int argc, char *argv[])
|
||||
return print_usage("unknown command");
|
||||
}
|
||||
|
||||
int DShotOutput::print_status()
|
||||
{
|
||||
const char *mode_str = nullptr;
|
||||
|
||||
switch (_mode) {
|
||||
|
||||
case MODE_NONE: mode_str = "no outputs"; break;
|
||||
|
||||
case MODE_1PWM: mode_str = "outputs1"; break;
|
||||
|
||||
case MODE_2PWM: mode_str = "outputs2"; break;
|
||||
|
||||
case MODE_2PWM2CAP: mode_str = "outputs2cap2"; break;
|
||||
|
||||
case MODE_3PWM: mode_str = "outputs3"; break;
|
||||
|
||||
case MODE_3PWM1CAP: mode_str = "outputs3cap1"; break;
|
||||
|
||||
case MODE_4PWM: mode_str = "outputs4"; break;
|
||||
|
||||
case MODE_4PWM1CAP: mode_str = "outputs4cap1"; break;
|
||||
|
||||
case MODE_4PWM2CAP: mode_str = "outputs4cap2"; break;
|
||||
|
||||
case MODE_5PWM: mode_str = "outputs5"; break;
|
||||
|
||||
case MODE_5PWM1CAP: mode_str = "outputs5cap1"; break;
|
||||
|
||||
case MODE_6PWM: mode_str = "outputs6"; break;
|
||||
|
||||
case MODE_8PWM: mode_str = "outputs8"; break;
|
||||
|
||||
case MODE_4CAP: mode_str = "cap4"; break;
|
||||
|
||||
case MODE_5CAP: mode_str = "cap5"; break;
|
||||
|
||||
case MODE_6CAP: mode_str = "cap6"; break;
|
||||
|
||||
default:
|
||||
break;
|
||||
}
|
||||
|
||||
if (mode_str) {
|
||||
PX4_INFO("Mode: %s", mode_str);
|
||||
}
|
||||
|
||||
PX4_INFO("Outputs initialized: %s", _outputs_initialized ? "yes" : "no");
|
||||
PX4_INFO("Outputs on: %s", _outputs_on ? "yes" : "no");
|
||||
perf_print_counter(_cycle_perf);
|
||||
_mixing_output.printStatus();
|
||||
|
||||
if (_telemetry) {
|
||||
PX4_INFO("telemetry on: %s", _telemetry_device);
|
||||
_telemetry->handler.printStatus();
|
||||
}
|
||||
|
||||
return 0;
|
||||
}
|
||||
|
||||
int DShotOutput::print_usage(const char *reason)
|
||||
{
|
||||
if (reason) {
|
||||
@@ -1614,68 +1673,7 @@ After saving, the reversed direction will be regarded as the normal one. So to r
|
||||
return 0;
|
||||
}
|
||||
|
||||
int DShotOutput::print_status()
|
||||
{
|
||||
const char *mode_str = nullptr;
|
||||
|
||||
switch (_mode) {
|
||||
|
||||
case MODE_NONE: mode_str = "no outputs"; break;
|
||||
|
||||
case MODE_1PWM: mode_str = "outputs1"; break;
|
||||
|
||||
case MODE_2PWM: mode_str = "outputs2"; break;
|
||||
|
||||
case MODE_2PWM2CAP: mode_str = "outputs2cap2"; break;
|
||||
|
||||
case MODE_3PWM: mode_str = "outputs3"; break;
|
||||
|
||||
case MODE_3PWM1CAP: mode_str = "outputs3cap1"; break;
|
||||
|
||||
case MODE_4PWM: mode_str = "outputs4"; break;
|
||||
|
||||
case MODE_4PWM1CAP: mode_str = "outputs4cap1"; break;
|
||||
|
||||
case MODE_4PWM2CAP: mode_str = "outputs4cap2"; break;
|
||||
|
||||
case MODE_5PWM: mode_str = "outputs5"; break;
|
||||
|
||||
case MODE_5PWM1CAP: mode_str = "outputs5cap1"; break;
|
||||
|
||||
case MODE_6PWM: mode_str = "outputs6"; break;
|
||||
|
||||
case MODE_8PWM: mode_str = "outputs8"; break;
|
||||
|
||||
case MODE_4CAP: mode_str = "cap4"; break;
|
||||
|
||||
case MODE_5CAP: mode_str = "cap5"; break;
|
||||
|
||||
case MODE_6CAP: mode_str = "cap6"; break;
|
||||
|
||||
default:
|
||||
break;
|
||||
}
|
||||
|
||||
if (mode_str) {
|
||||
PX4_INFO("Mode: %s", mode_str);
|
||||
}
|
||||
|
||||
PX4_INFO("Outputs initialized: %s", _outputs_initialized ? "yes" : "no");
|
||||
PX4_INFO("Outputs on: %s", _outputs_on ? "yes" : "no");
|
||||
perf_print_counter(_cycle_perf);
|
||||
_mixing_output.printStatus();
|
||||
if (_telemetry) {
|
||||
PX4_INFO("telemetry on: %s", _telemetry_device);
|
||||
_telemetry->handler.printStatus();
|
||||
}
|
||||
|
||||
return 0;
|
||||
}
|
||||
|
||||
extern "C" __EXPORT int dshot_main(int argc, char *argv[]);
|
||||
|
||||
int
|
||||
dshot_main(int argc, char *argv[])
|
||||
extern "C" __EXPORT int dshot_main(int argc, char *argv[])
|
||||
{
|
||||
return DShotOutput::main(argc, argv);
|
||||
}
|
||||
|
||||
@@ -39,8 +39,6 @@
|
||||
#include <uORB/Subscription.hpp>
|
||||
#include <uORB/topics/parameter_update.h>
|
||||
|
||||
extern "C" __EXPORT int pwm_out_sim_main(int argc, char *argv[]);
|
||||
|
||||
PWMSim::PWMSim(bool hil_mode_enabled) :
|
||||
CDev(PWM_OUTPUT0_DEVICE_PATH),
|
||||
OutputModuleInterface(MODULE_NAME, px4::wq_configurations::hp_default)
|
||||
@@ -273,6 +271,12 @@ int PWMSim::custom_command(int argc, char *argv[])
|
||||
return print_usage("unknown command");
|
||||
}
|
||||
|
||||
int PWMSim::print_status()
|
||||
{
|
||||
_mixing_output.printStatus();
|
||||
return 0;
|
||||
}
|
||||
|
||||
int PWMSim::print_usage(const char *reason)
|
||||
{
|
||||
if (reason) {
|
||||
@@ -300,14 +304,7 @@ It is used in SITL and HITL.
|
||||
return 0;
|
||||
}
|
||||
|
||||
int PWMSim::print_status()
|
||||
{
|
||||
_mixing_output.printStatus();
|
||||
return 0;
|
||||
}
|
||||
|
||||
int
|
||||
pwm_out_sim_main(int argc, char *argv[])
|
||||
extern "C" __EXPORT int pwm_out_sim_main(int argc, char *argv[])
|
||||
{
|
||||
return PWMSim::main(argc, argv);
|
||||
}
|
||||
|
||||
+54
-58
@@ -2173,6 +2173,59 @@ int PX4FMU::custom_command(int argc, char *argv[])
|
||||
return print_usage("unknown command");
|
||||
}
|
||||
|
||||
int PX4FMU::print_status()
|
||||
{
|
||||
PX4_INFO("Max update rate: %i Hz", _current_update_rate);
|
||||
|
||||
const char *mode_str = nullptr;
|
||||
|
||||
switch (_mode) {
|
||||
case MODE_NONE: mode_str = "no pwm"; break;
|
||||
|
||||
case MODE_1PWM: mode_str = "pwm1"; break;
|
||||
|
||||
case MODE_2PWM: mode_str = "pwm2"; break;
|
||||
|
||||
case MODE_2PWM2CAP: mode_str = "pwm2cap2"; break;
|
||||
|
||||
case MODE_3PWM: mode_str = "pwm3"; break;
|
||||
|
||||
case MODE_3PWM1CAP: mode_str = "pwm3cap1"; break;
|
||||
|
||||
case MODE_4PWM: mode_str = "pwm4"; break;
|
||||
|
||||
case MODE_4PWM1CAP: mode_str = "pwm4cap1"; break;
|
||||
|
||||
case MODE_4PWM2CAP: mode_str = "pwm4cap2"; break;
|
||||
|
||||
case MODE_5PWM: mode_str = "pwm5"; break;
|
||||
|
||||
case MODE_5PWM1CAP: mode_str = "pwm5cap1"; break;
|
||||
|
||||
case MODE_6PWM: mode_str = "pwm6"; break;
|
||||
|
||||
case MODE_8PWM: mode_str = "pwm8"; break;
|
||||
|
||||
case MODE_4CAP: mode_str = "cap4"; break;
|
||||
|
||||
case MODE_5CAP: mode_str = "cap5"; break;
|
||||
|
||||
case MODE_6CAP: mode_str = "cap6"; break;
|
||||
|
||||
default:
|
||||
break;
|
||||
}
|
||||
|
||||
if (mode_str) {
|
||||
PX4_INFO("PWM Mode: %s", mode_str);
|
||||
}
|
||||
|
||||
perf_print_counter(_cycle_perf);
|
||||
_mixing_output.printStatus();
|
||||
|
||||
return 0;
|
||||
}
|
||||
|
||||
int PX4FMU::print_usage(const char *reason)
|
||||
{
|
||||
if (reason) {
|
||||
@@ -2252,64 +2305,7 @@ mixer files.
|
||||
return 0;
|
||||
}
|
||||
|
||||
int PX4FMU::print_status()
|
||||
{
|
||||
PX4_INFO("Max update rate: %i Hz", _current_update_rate);
|
||||
|
||||
const char *mode_str = nullptr;
|
||||
|
||||
switch (_mode) {
|
||||
|
||||
case MODE_NONE: mode_str = "no pwm"; break;
|
||||
|
||||
case MODE_1PWM: mode_str = "pwm1"; break;
|
||||
|
||||
case MODE_2PWM: mode_str = "pwm2"; break;
|
||||
|
||||
case MODE_2PWM2CAP: mode_str = "pwm2cap2"; break;
|
||||
|
||||
case MODE_3PWM: mode_str = "pwm3"; break;
|
||||
|
||||
case MODE_3PWM1CAP: mode_str = "pwm3cap1"; break;
|
||||
|
||||
case MODE_4PWM: mode_str = "pwm4"; break;
|
||||
|
||||
case MODE_4PWM1CAP: mode_str = "pwm4cap1"; break;
|
||||
|
||||
case MODE_4PWM2CAP: mode_str = "pwm4cap2"; break;
|
||||
|
||||
case MODE_5PWM: mode_str = "pwm5"; break;
|
||||
|
||||
case MODE_5PWM1CAP: mode_str = "pwm5cap1"; break;
|
||||
|
||||
case MODE_6PWM: mode_str = "pwm6"; break;
|
||||
|
||||
case MODE_8PWM: mode_str = "pwm8"; break;
|
||||
|
||||
case MODE_4CAP: mode_str = "cap4"; break;
|
||||
|
||||
case MODE_5CAP: mode_str = "cap5"; break;
|
||||
|
||||
case MODE_6CAP: mode_str = "cap6"; break;
|
||||
|
||||
default:
|
||||
break;
|
||||
}
|
||||
|
||||
if (mode_str) {
|
||||
PX4_INFO("PWM Mode: %s", mode_str);
|
||||
}
|
||||
|
||||
perf_print_counter(_cycle_perf);
|
||||
_mixing_output.printStatus();
|
||||
|
||||
return 0;
|
||||
}
|
||||
|
||||
extern "C" __EXPORT int fmu_main(int argc, char *argv[]);
|
||||
|
||||
int
|
||||
fmu_main(int argc, char *argv[])
|
||||
extern "C" __EXPORT int fmu_main(int argc, char *argv[])
|
||||
{
|
||||
return PX4FMU::main(argc, argv);
|
||||
}
|
||||
|
||||
@@ -768,7 +768,38 @@ int RCInput::custom_command(int argc, char *argv[])
|
||||
return print_usage("unknown command");
|
||||
}
|
||||
|
||||
int RCInput::print_usage(const char *reason)
|
||||
int RCInput::print_status()
|
||||
{
|
||||
PX4_INFO("Running %s", (_run_as_task ? "as task" : "on work queue"));
|
||||
|
||||
if (!_run_as_task) {
|
||||
PX4_INFO("Max update rate: %i Hz", 1000000 / _current_update_interval);
|
||||
}
|
||||
|
||||
if (_device[0] != '\0') {
|
||||
PX4_INFO("Serial device: %s", _device);
|
||||
}
|
||||
|
||||
PX4_INFO("RC scan state: %s, locked: %s", RC_SCAN_STRING[_rc_scan_state], _rc_scan_locked ? "yes" : "no");
|
||||
PX4_INFO("CRSF Telemetry: %s", _crsf_telemetry ? "yes" : "no");
|
||||
PX4_INFO("SBUS frame drops: %u", sbus_dropped_frames());
|
||||
|
||||
#if ADC_RC_RSSI_CHANNEL
|
||||
PX4_INFO("vrssi: %dmV", (int)(_analog_rc_rssi_volt * 1000.0f));
|
||||
#endif
|
||||
|
||||
perf_print_counter(_cycle_perf);
|
||||
perf_print_counter(_publish_interval_perf);
|
||||
|
||||
if (hrt_elapsed_time(&_rc_in.timestamp) < 1_s) {
|
||||
print_message(_rc_in);
|
||||
}
|
||||
|
||||
return 0;
|
||||
}
|
||||
|
||||
int
|
||||
RCInput::print_usage(const char *reason)
|
||||
{
|
||||
if (reason) {
|
||||
PX4_WARN("%s\n", reason);
|
||||
@@ -805,39 +836,7 @@ When running on the work queue, it schedules at a fixed frequency.
|
||||
return 0;
|
||||
}
|
||||
|
||||
int RCInput::print_status()
|
||||
{
|
||||
PX4_INFO("Running %s", (_run_as_task ? "as task" : "on work queue"));
|
||||
|
||||
if (!_run_as_task) {
|
||||
PX4_INFO("Max update rate: %i Hz", 1000000 / _current_update_interval);
|
||||
}
|
||||
if (_device[0] != '\0') {
|
||||
PX4_INFO("Serial device: %s", _device);
|
||||
}
|
||||
|
||||
PX4_INFO("RC scan state: %s, locked: %s", RC_SCAN_STRING[_rc_scan_state], _rc_scan_locked ? "yes" : "no");
|
||||
PX4_INFO("CRSF Telemetry: %s", _crsf_telemetry ? "yes" : "no");
|
||||
PX4_INFO("SBUS frame drops: %u", sbus_dropped_frames());
|
||||
|
||||
#if ADC_RC_RSSI_CHANNEL
|
||||
PX4_INFO("vrssi: %dmV", (int)(_analog_rc_rssi_volt * 1000.0f));
|
||||
#endif
|
||||
|
||||
perf_print_counter(_cycle_perf);
|
||||
perf_print_counter(_publish_interval_perf);
|
||||
|
||||
if (hrt_elapsed_time(&_rc_in.timestamp) < 1_s) {
|
||||
print_message(_rc_in);
|
||||
}
|
||||
|
||||
return 0;
|
||||
}
|
||||
|
||||
extern "C" __EXPORT int rc_input_main(int argc, char *argv[]);
|
||||
|
||||
int
|
||||
rc_input_main(int argc, char *argv[])
|
||||
extern "C" __EXPORT int rc_input_main(int argc, char *argv[])
|
||||
{
|
||||
return RCInput::main(argc, argv);
|
||||
}
|
||||
|
||||
@@ -199,6 +199,14 @@ SafetyButton::custom_command(int argc, char *argv[])
|
||||
return print_usage("unknown command");
|
||||
}
|
||||
|
||||
int
|
||||
SafetyButton::print_status()
|
||||
{
|
||||
PX4_INFO("Safety State (from button): %s", _safety_btn_off ? "off" : "on");
|
||||
|
||||
return 0;
|
||||
}
|
||||
|
||||
int
|
||||
SafetyButton::print_usage(const char *reason)
|
||||
{
|
||||
@@ -219,18 +227,7 @@ This module is responsible for the safety button.
|
||||
return 0;
|
||||
}
|
||||
|
||||
int
|
||||
SafetyButton::print_status()
|
||||
{
|
||||
PX4_INFO("Safety State (from button): %s", _safety_btn_off ? "off" : "on");
|
||||
|
||||
return 0;
|
||||
}
|
||||
|
||||
extern "C" __EXPORT int safety_button_main(int argc, char *argv[]);
|
||||
|
||||
int
|
||||
safety_button_main(int argc, char *argv[])
|
||||
extern "C" __EXPORT int safety_button_main(int argc, char *argv[])
|
||||
{
|
||||
return SafetyButton::main(argc, argv);
|
||||
}
|
||||
|
||||
@@ -778,9 +778,7 @@ tap_esc start -d /dev/ttyS2 -n <1-8>
|
||||
return PX4_OK;
|
||||
}
|
||||
|
||||
extern "C" __EXPORT int tap_esc_main(int argc, char *argv[]);
|
||||
|
||||
int tap_esc_main(int argc, char *argv[])
|
||||
extern "C" __EXPORT int tap_esc_main(int argc, char *argv[])
|
||||
{
|
||||
return TAP_ESC::main(argc, argv);
|
||||
}
|
||||
|
||||
@@ -207,23 +207,6 @@ static void set_uart_single_wire(int uart, bool single_wire)
|
||||
}
|
||||
}
|
||||
|
||||
/**
|
||||
* Print command usage information
|
||||
*/
|
||||
static void usage()
|
||||
{
|
||||
PRINT_MODULE_DESCRIPTION("FrSky Telemetry support. Auto-detects D or S.PORT protocol.");
|
||||
|
||||
PRINT_MODULE_USAGE_NAME("frsky_telemetry", "communication");
|
||||
PRINT_MODULE_USAGE_COMMAND("start");
|
||||
PRINT_MODULE_USAGE_PARAM_STRING('d', "/dev/ttyS6", "<file:dev>", "Select Serial Device", true);
|
||||
PRINT_MODULE_USAGE_PARAM_INT('t', 0, 0, 60, "Scanning timeout [s] (default: no timeout)", true);
|
||||
PRINT_MODULE_USAGE_PARAM_STRING('m', "auto", "sport|sport_single|dtype", "Select protocol (default: auto-detect)",
|
||||
true);
|
||||
PRINT_MODULE_USAGE_COMMAND("stop");
|
||||
PRINT_MODULE_USAGE_COMMAND("status");
|
||||
}
|
||||
|
||||
/**
|
||||
* The daemon thread.
|
||||
*/
|
||||
@@ -806,3 +789,20 @@ int frsky_telemetry_main(int argc, char *argv[])
|
||||
usage();
|
||||
return 0;
|
||||
}
|
||||
|
||||
/**
|
||||
* Print command usage information
|
||||
*/
|
||||
static void usage()
|
||||
{
|
||||
PRINT_MODULE_DESCRIPTION("FrSky Telemetry support. Auto-detects D or S.PORT protocol.");
|
||||
|
||||
PRINT_MODULE_USAGE_NAME("frsky_telemetry", "communication");
|
||||
PRINT_MODULE_USAGE_COMMAND("start");
|
||||
PRINT_MODULE_USAGE_PARAM_STRING('d', "/dev/ttyS6", "<file:dev>", "Select Serial Device", true);
|
||||
PRINT_MODULE_USAGE_PARAM_INT('t', 0, 0, 60, "Scanning timeout [s] (default: no timeout)", true);
|
||||
PRINT_MODULE_USAGE_PARAM_STRING('m', "auto", "sport|sport_single|dtype", "Select protocol (default: auto-detect)",
|
||||
true);
|
||||
PRINT_MODULE_USAGE_COMMAND("stop");
|
||||
PRINT_MODULE_USAGE_COMMAND("status");
|
||||
}
|
||||
|
||||
@@ -536,6 +536,19 @@ int AirspeedModule::custom_command(int argc, char *argv[])
|
||||
return print_usage("unknown command");
|
||||
}
|
||||
|
||||
int AirspeedModule::print_status()
|
||||
{
|
||||
perf_print_counter(_perf_elapsed);
|
||||
|
||||
int instance = 0;
|
||||
uORB::SubscriptionData<airspeed_validated_s> est{ORB_ID(airspeed_validated), (uint8_t)instance};
|
||||
est.update();
|
||||
PX4_INFO("Number of airspeed sensors: %i", _number_of_airspeed_sensors);
|
||||
print_message(est.get());
|
||||
|
||||
return 0;
|
||||
}
|
||||
|
||||
int AirspeedModule::print_usage(const char *reason)
|
||||
{
|
||||
if (reason) {
|
||||
@@ -562,23 +575,7 @@ and also publishes those.
|
||||
return 0;
|
||||
}
|
||||
|
||||
int AirspeedModule::print_status()
|
||||
{
|
||||
perf_print_counter(_perf_elapsed);
|
||||
|
||||
int instance = 0;
|
||||
uORB::SubscriptionData<airspeed_validated_s> est{ORB_ID(airspeed_validated), (uint8_t)instance};
|
||||
est.update();
|
||||
PX4_INFO("Number of airspeed sensors: %i", _number_of_airspeed_sensors);
|
||||
print_message(est.get());
|
||||
|
||||
return 0;
|
||||
}
|
||||
|
||||
extern "C" __EXPORT int airspeed_selector_main(int argc, char *argv[]);
|
||||
|
||||
int
|
||||
airspeed_selector_main(int argc, char *argv[])
|
||||
extern "C" __EXPORT int airspeed_selector_main(int argc, char *argv[])
|
||||
{
|
||||
return AirspeedModule::main(argc, argv);
|
||||
}
|
||||
|
||||
@@ -514,38 +514,6 @@ int commander_main(int argc, char *argv[])
|
||||
return 1;
|
||||
}
|
||||
|
||||
void usage(const char *reason)
|
||||
{
|
||||
if (reason) {
|
||||
PX4_INFO("%s", reason);
|
||||
}
|
||||
|
||||
PRINT_MODULE_DESCRIPTION(
|
||||
R"DESCR_STR(
|
||||
### Description
|
||||
The commander module contains the state machine for mode switching and failsafe behavior.
|
||||
)DESCR_STR");
|
||||
|
||||
PRINT_MODULE_USAGE_NAME("commander", "system");
|
||||
PRINT_MODULE_USAGE_COMMAND("start");
|
||||
PRINT_MODULE_USAGE_PARAM_FLAG('h', "Enable HIL mode", true);
|
||||
PRINT_MODULE_USAGE_COMMAND_DESCR("calibrate", "Run sensor calibration");
|
||||
PRINT_MODULE_USAGE_ARG("mag|accel|gyro|level|esc|airspeed", "Calibration type", false);
|
||||
PRINT_MODULE_USAGE_COMMAND_DESCR("check", "Run preflight checks");
|
||||
PRINT_MODULE_USAGE_COMMAND("arm");
|
||||
PRINT_MODULE_USAGE_PARAM_FLAG('f', "Force arming (do not run preflight checks)", true);
|
||||
PRINT_MODULE_USAGE_COMMAND("disarm");
|
||||
PRINT_MODULE_USAGE_COMMAND("takeoff");
|
||||
PRINT_MODULE_USAGE_COMMAND("land");
|
||||
PRINT_MODULE_USAGE_COMMAND_DESCR("transition", "VTOL transition");
|
||||
PRINT_MODULE_USAGE_COMMAND_DESCR("mode", "Change flight mode");
|
||||
PRINT_MODULE_USAGE_ARG("manual|acro|offboard|stabilized|rattitude|altctl|posctl|auto:mission|auto:loiter|auto:rtl|auto:takeoff|auto:land|auto:precland",
|
||||
"Flight mode", false);
|
||||
PRINT_MODULE_USAGE_COMMAND("lockdown");
|
||||
PRINT_MODULE_USAGE_ARG("off", "Turn lockdown off", true);
|
||||
PRINT_MODULE_USAGE_DEFAULT_COMMANDS();
|
||||
}
|
||||
|
||||
void print_status()
|
||||
{
|
||||
PX4_INFO("arming: %s", arming_state_names[status.arming_state]);
|
||||
@@ -812,6 +780,7 @@ Commander::handle_command(vehicle_status_s *status_local, const vehicle_command_
|
||||
if (cmd_arms) {
|
||||
if (armed_local->armed) {
|
||||
mavlink_log_warning(&mavlink_log_pub, "Arming denied! Already armed");
|
||||
|
||||
} else {
|
||||
mavlink_log_critical(&mavlink_log_pub, "Arming denied! Not landed");
|
||||
}
|
||||
@@ -841,18 +810,18 @@ Commander::handle_command(vehicle_status_s *status_local, const vehicle_command_
|
||||
const bool throttle_above_center = (sp_man.z > 0.6f);
|
||||
|
||||
if (cmd_arms && throttle_above_center &&
|
||||
(status_local->nav_state == vehicle_status_s::NAVIGATION_STATE_POSCTL ||
|
||||
status_local->nav_state == vehicle_status_s::NAVIGATION_STATE_ALTCTL)) {
|
||||
(status_local->nav_state == vehicle_status_s::NAVIGATION_STATE_POSCTL ||
|
||||
status_local->nav_state == vehicle_status_s::NAVIGATION_STATE_ALTCTL)) {
|
||||
mavlink_log_critical(&mavlink_log_pub, "Arming denied! Throttle not centered");
|
||||
cmd_result = vehicle_command_s::VEHICLE_CMD_RESULT_DENIED;
|
||||
break;
|
||||
}
|
||||
|
||||
if (cmd_arms && throttle_above_low &&
|
||||
(status_local->nav_state == vehicle_status_s::NAVIGATION_STATE_MANUAL ||
|
||||
status_local->nav_state == vehicle_status_s::NAVIGATION_STATE_ACRO ||
|
||||
status_local->nav_state == vehicle_status_s::NAVIGATION_STATE_STAB ||
|
||||
status_local->nav_state == vehicle_status_s::NAVIGATION_STATE_RATTITUDE)) {
|
||||
(status_local->nav_state == vehicle_status_s::NAVIGATION_STATE_MANUAL ||
|
||||
status_local->nav_state == vehicle_status_s::NAVIGATION_STATE_ACRO ||
|
||||
status_local->nav_state == vehicle_status_s::NAVIGATION_STATE_STAB ||
|
||||
status_local->nav_state == vehicle_status_s::NAVIGATION_STATE_RATTITUDE)) {
|
||||
mavlink_log_critical(&mavlink_log_pub, "Arming denied! Throttle not zero");
|
||||
cmd_result = vehicle_command_s::VEHICLE_CMD_RESULT_DENIED;
|
||||
break;
|
||||
@@ -1090,12 +1059,16 @@ Commander::handle_command(vehicle_status_s *status_local, const vehicle_command_
|
||||
break;
|
||||
|
||||
case vehicle_command_s::VEHICLE_CMD_DO_ORBIT:
|
||||
|
||||
// Switch to orbit state and let the orbit task handle the command further
|
||||
if (TRANSITION_DENIED != main_state_transition(*status_local, commander_state_s::MAIN_STATE_ORBIT, status_flags, &internal_state)) {
|
||||
if (TRANSITION_DENIED != main_state_transition(*status_local, commander_state_s::MAIN_STATE_ORBIT, status_flags,
|
||||
&internal_state)) {
|
||||
cmd_result = vehicle_command_s::VEHICLE_CMD_RESULT_ACCEPTED;
|
||||
|
||||
} else {
|
||||
cmd_result = vehicle_command_s::VEHICLE_CMD_RESULT_TEMPORARILY_REJECTED;
|
||||
}
|
||||
|
||||
break;
|
||||
|
||||
case vehicle_command_s::VEHICLE_CMD_DO_MOTOR_TEST:
|
||||
@@ -1166,24 +1139,32 @@ Commander::handle_command_motor_test(const vehicle_command_s &cmd)
|
||||
test_motor.timestamp = hrt_absolute_time();
|
||||
test_motor.motor_number = (int)(cmd.param1 + 0.5f) - 1;
|
||||
int throttle_type = (int)(cmd.param2 + 0.5f);
|
||||
|
||||
if (throttle_type != 0) { // 0: MOTOR_TEST_THROTTLE_PERCENT
|
||||
return vehicle_command_s::VEHICLE_CMD_RESULT_UNSUPPORTED;
|
||||
}
|
||||
int motor_count = (int) (cmd.param5 + 0.5);
|
||||
|
||||
int motor_count = (int)(cmd.param5 + 0.5);
|
||||
|
||||
if (motor_count > 1) {
|
||||
return vehicle_command_s::VEHICLE_CMD_RESULT_UNSUPPORTED;
|
||||
}
|
||||
|
||||
test_motor.action = test_motor_s::ACTION_RUN;
|
||||
test_motor.value = math::constrain(cmd.param3 / 100.f, 0.f, 1.f);
|
||||
|
||||
if (test_motor.value < FLT_EPSILON) {
|
||||
// the message spec is not clear on whether 0 means stop, but it should be closer to what a user expects
|
||||
test_motor.value = -1.f;
|
||||
}
|
||||
|
||||
test_motor.timeout_ms = (int)(cmd.param4 * 1000.f + 0.5f);
|
||||
|
||||
// enforce a timeout and a maximum limit
|
||||
if (test_motor.timeout_ms == 0 || test_motor.timeout_ms > 3000) {
|
||||
test_motor.timeout_ms = 3000;
|
||||
}
|
||||
|
||||
test_motor.driver_instance = 0; // the mavlink command does not allow to specify the instance, so set to 0 for now
|
||||
_test_motor_pub.publish(test_motor);
|
||||
|
||||
@@ -1799,6 +1780,7 @@ Commander::run()
|
||||
|
||||
/* update subsystem info which arrives from outside of commander*/
|
||||
subsystem_info_s info;
|
||||
|
||||
while (subsys_sub.update(&info)) {
|
||||
set_health_flags(info.subsystem_type, info.present, info.enabled, info.ok, status);
|
||||
status_changed = true;
|
||||
@@ -2411,6 +2393,7 @@ Commander::run()
|
||||
/* safety switch is not present, do not go into prearmed */
|
||||
armed.prearmed = false;
|
||||
}
|
||||
|
||||
break;
|
||||
|
||||
default:
|
||||
@@ -2526,13 +2509,20 @@ Commander::run()
|
||||
void
|
||||
Commander::get_circuit_breaker_params()
|
||||
{
|
||||
status_flags.circuit_breaker_engaged_power_check = circuit_breaker_enabled_by_val(_param_cbrk_supply_chk.get(), CBRK_SUPPLY_CHK_KEY);
|
||||
status_flags.circuit_breaker_engaged_usb_check = circuit_breaker_enabled_by_val(_param_cbrk_usb_chk.get(), CBRK_USB_CHK_KEY);
|
||||
status_flags.circuit_breaker_engaged_airspd_check = circuit_breaker_enabled_by_val(_param_cbrk_airspd_chk.get(), CBRK_AIRSPD_CHK_KEY);
|
||||
status_flags.circuit_breaker_engaged_enginefailure_check = circuit_breaker_enabled_by_val(_param_cbrk_enginefail.get(), CBRK_ENGINEFAIL_KEY);
|
||||
status_flags.circuit_breaker_engaged_gpsfailure_check = circuit_breaker_enabled_by_val(_param_cbrk_gpsfail.get(), CBRK_GPSFAIL_KEY);
|
||||
status_flags.circuit_breaker_flight_termination_disabled = circuit_breaker_enabled_by_val(_param_cbrk_flightterm.get(), CBRK_FLIGHTTERM_KEY);
|
||||
status_flags.circuit_breaker_engaged_posfailure_check = circuit_breaker_enabled_by_val(_param_cbrk_velposerr.get(), CBRK_VELPOSERR_KEY);
|
||||
status_flags.circuit_breaker_engaged_power_check = circuit_breaker_enabled_by_val(_param_cbrk_supply_chk.get(),
|
||||
CBRK_SUPPLY_CHK_KEY);
|
||||
status_flags.circuit_breaker_engaged_usb_check = circuit_breaker_enabled_by_val(_param_cbrk_usb_chk.get(),
|
||||
CBRK_USB_CHK_KEY);
|
||||
status_flags.circuit_breaker_engaged_airspd_check = circuit_breaker_enabled_by_val(_param_cbrk_airspd_chk.get(),
|
||||
CBRK_AIRSPD_CHK_KEY);
|
||||
status_flags.circuit_breaker_engaged_enginefailure_check = circuit_breaker_enabled_by_val(_param_cbrk_enginefail.get(),
|
||||
CBRK_ENGINEFAIL_KEY);
|
||||
status_flags.circuit_breaker_engaged_gpsfailure_check = circuit_breaker_enabled_by_val(_param_cbrk_gpsfail.get(),
|
||||
CBRK_GPSFAIL_KEY);
|
||||
status_flags.circuit_breaker_flight_termination_disabled = circuit_breaker_enabled_by_val(_param_cbrk_flightterm.get(),
|
||||
CBRK_FLIGHTTERM_KEY);
|
||||
status_flags.circuit_breaker_engaged_posfailure_check = circuit_breaker_enabled_by_val(_param_cbrk_velposerr.get(),
|
||||
CBRK_VELPOSERR_KEY);
|
||||
}
|
||||
|
||||
void
|
||||
@@ -2697,7 +2687,8 @@ Commander::set_main_state(const vehicle_status_s &status_local, bool *changed)
|
||||
transition_result_t
|
||||
Commander::set_main_state_override_on(const vehicle_status_s &status_local, bool *changed)
|
||||
{
|
||||
const transition_result_t res = main_state_transition(status_local, commander_state_s::MAIN_STATE_MANUAL, status_flags, &internal_state);
|
||||
const transition_result_t res = main_state_transition(status_local, commander_state_s::MAIN_STATE_MANUAL, status_flags,
|
||||
&internal_state);
|
||||
*changed = (res == TRANSITION_CHANGED);
|
||||
|
||||
return res;
|
||||
@@ -3767,7 +3758,7 @@ bool Commander::preflight_check(bool report)
|
||||
const bool checkGNSS = (arm_requirements & ARM_REQ_GPS_BIT);
|
||||
|
||||
const bool success = Preflight::preflightCheck(&mavlink_log_pub, status, status_flags, checkGNSS, report, false,
|
||||
hrt_elapsed_time(&commander_boot_timestamp));
|
||||
hrt_elapsed_time(&commander_boot_timestamp));
|
||||
|
||||
if (success) {
|
||||
status_flags.condition_system_sensors_initialized = true;
|
||||
@@ -4497,3 +4488,35 @@ void Commander::esc_status_check(const esc_status_s &esc_status)
|
||||
status_flags.condition_escs_error = true;
|
||||
}
|
||||
}
|
||||
|
||||
void usage(const char *reason)
|
||||
{
|
||||
if (reason) {
|
||||
PX4_INFO("%s", reason);
|
||||
}
|
||||
|
||||
PRINT_MODULE_DESCRIPTION(
|
||||
R"DESCR_STR(
|
||||
### Description
|
||||
The commander module contains the state machine for mode switching and failsafe behavior.
|
||||
)DESCR_STR");
|
||||
|
||||
PRINT_MODULE_USAGE_NAME("commander", "system");
|
||||
PRINT_MODULE_USAGE_COMMAND("start");
|
||||
PRINT_MODULE_USAGE_PARAM_FLAG('h', "Enable HIL mode", true);
|
||||
PRINT_MODULE_USAGE_COMMAND_DESCR("calibrate", "Run sensor calibration");
|
||||
PRINT_MODULE_USAGE_ARG("mag|accel|gyro|level|esc|airspeed", "Calibration type", false);
|
||||
PRINT_MODULE_USAGE_COMMAND_DESCR("check", "Run preflight checks");
|
||||
PRINT_MODULE_USAGE_COMMAND("arm");
|
||||
PRINT_MODULE_USAGE_PARAM_FLAG('f', "Force arming (do not run preflight checks)", true);
|
||||
PRINT_MODULE_USAGE_COMMAND("disarm");
|
||||
PRINT_MODULE_USAGE_COMMAND("takeoff");
|
||||
PRINT_MODULE_USAGE_COMMAND("land");
|
||||
PRINT_MODULE_USAGE_COMMAND_DESCR("transition", "VTOL transition");
|
||||
PRINT_MODULE_USAGE_COMMAND_DESCR("mode", "Change flight mode");
|
||||
PRINT_MODULE_USAGE_ARG("manual|acro|offboard|stabilized|rattitude|altctl|posctl|auto:mission|auto:loiter|auto:rtl|auto:takeoff|auto:land|auto:precland",
|
||||
"Flight mode", false);
|
||||
PRINT_MODULE_USAGE_COMMAND("lockdown");
|
||||
PRINT_MODULE_USAGE_ARG("off", "Turn lockdown off", true);
|
||||
PRINT_MODULE_USAGE_DEFAULT_COMMANDS();
|
||||
}
|
||||
|
||||
@@ -92,8 +92,6 @@
|
||||
using math::constrain;
|
||||
using namespace time_literals;
|
||||
|
||||
extern "C" __EXPORT int ekf2_main(int argc, char *argv[]);
|
||||
|
||||
class Ekf2 final : public ModuleBase<Ekf2>, public ModuleParams, public px4::WorkItem
|
||||
{
|
||||
public:
|
||||
@@ -2368,35 +2366,10 @@ int Ekf2::custom_command(int argc, char *argv[])
|
||||
return print_usage("unknown command");
|
||||
}
|
||||
|
||||
int Ekf2::print_usage(const char *reason)
|
||||
{
|
||||
if (reason) {
|
||||
PX4_WARN("%s\n", reason);
|
||||
}
|
||||
|
||||
PRINT_MODULE_DESCRIPTION(
|
||||
R"DESCR_STR(
|
||||
### Description
|
||||
Attitude and position estimator using an Extended Kalman Filter. It is used for Multirotors and Fixed-Wing.
|
||||
|
||||
The documentation can be found on the [ECL/EKF Overview & Tuning](https://docs.px4.io/en/advanced_config/tuning_the_ecl_ekf.html) page.
|
||||
|
||||
ekf2 can be started in replay mode (`-r`): in this mode it does not access the system time, but only uses the
|
||||
timestamps from the sensor topics.
|
||||
|
||||
)DESCR_STR");
|
||||
|
||||
PRINT_MODULE_USAGE_NAME("ekf2", "estimator");
|
||||
PRINT_MODULE_USAGE_COMMAND("start");
|
||||
PRINT_MODULE_USAGE_PARAM_FLAG('r', "Enable replay mode", true);
|
||||
PRINT_MODULE_USAGE_DEFAULT_COMMANDS();
|
||||
|
||||
return 0;
|
||||
}
|
||||
|
||||
int Ekf2::task_spawn(int argc, char *argv[])
|
||||
{
|
||||
bool replay_mode = false;
|
||||
|
||||
if (argc > 1 && !strcmp(argv[1], "-r")) {
|
||||
PX4_INFO("replay mode enabled");
|
||||
replay_mode = true;
|
||||
@@ -2423,7 +2396,33 @@ int Ekf2::task_spawn(int argc, char *argv[])
|
||||
return PX4_ERROR;
|
||||
}
|
||||
|
||||
int ekf2_main(int argc, char *argv[])
|
||||
int Ekf2::print_usage(const char *reason)
|
||||
{
|
||||
if (reason) {
|
||||
PX4_WARN("%s\n", reason);
|
||||
}
|
||||
|
||||
PRINT_MODULE_DESCRIPTION(
|
||||
R"DESCR_STR(
|
||||
### Description
|
||||
Attitude and position estimator using an Extended Kalman Filter. It is used for Multirotors and Fixed-Wing.
|
||||
|
||||
The documentation can be found on the [ECL/EKF Overview & Tuning](https://docs.px4.io/en/advanced_config/tuning_the_ecl_ekf.html) page.
|
||||
|
||||
ekf2 can be started in replay mode (`-r`): in this mode it does not access the system time, but only uses the
|
||||
timestamps from the sensor topics.
|
||||
|
||||
)DESCR_STR");
|
||||
|
||||
PRINT_MODULE_USAGE_NAME("ekf2", "estimator");
|
||||
PRINT_MODULE_USAGE_COMMAND("start");
|
||||
PRINT_MODULE_USAGE_PARAM_FLAG('r', "Enable replay mode", true);
|
||||
PRINT_MODULE_USAGE_DEFAULT_COMMANDS();
|
||||
|
||||
return 0;
|
||||
}
|
||||
|
||||
extern "C" __EXPORT int ekf2_main(int argc, char *argv[])
|
||||
{
|
||||
return Ekf2::main(argc, argv);
|
||||
}
|
||||
|
||||
@@ -201,32 +201,6 @@ void SendEvent::answer_command(const vehicle_command_s &cmd, unsigned result)
|
||||
command_ack_pub.publish(command_ack);
|
||||
}
|
||||
|
||||
int SendEvent::print_usage(const char *reason)
|
||||
{
|
||||
if (reason) {
|
||||
printf("%s\n\n", reason);
|
||||
}
|
||||
|
||||
PRINT_MODULE_DESCRIPTION(
|
||||
R"DESCR_STR(
|
||||
### Description
|
||||
Background process running periodically on the LP work queue to perform housekeeping tasks.
|
||||
It is currently only responsible for temperature calibration and tone alarm on RC Loss.
|
||||
|
||||
The tasks can be started via CLI or uORB topics (vehicle_command from MAVLink, etc.).
|
||||
)DESCR_STR");
|
||||
|
||||
PRINT_MODULE_USAGE_NAME("send_event", "system");
|
||||
PRINT_MODULE_USAGE_COMMAND_DESCR("start", "Start the background task");
|
||||
PRINT_MODULE_USAGE_COMMAND_DESCR("temperature_calibration", "Run temperature calibration process");
|
||||
PRINT_MODULE_USAGE_PARAM_FLAG('g', "calibrate the gyro", true);
|
||||
PRINT_MODULE_USAGE_PARAM_FLAG('a', "calibrate the accel", true);
|
||||
PRINT_MODULE_USAGE_PARAM_FLAG('b', "calibrate the baro (if none of these is given, all will be calibrated)", true);
|
||||
PRINT_MODULE_USAGE_DEFAULT_COMMANDS();
|
||||
|
||||
return 0;
|
||||
}
|
||||
|
||||
int SendEvent::custom_command(int argc, char *argv[])
|
||||
{
|
||||
if (!strcmp(argv[0], "temperature_calibration")) {
|
||||
@@ -267,13 +241,16 @@ int SendEvent::custom_command(int argc, char *argv[])
|
||||
|
||||
vehicle_command_s vcmd{};
|
||||
vcmd.timestamp = hrt_absolute_time();
|
||||
vcmd.param1 = (float)((gyro_calib || calib_all) ? vehicle_command_s::PREFLIGHT_CALIBRATION_TEMPERATURE_CALIBRATION : NAN);
|
||||
vcmd.param1 = (float)((gyro_calib
|
||||
|| calib_all) ? vehicle_command_s::PREFLIGHT_CALIBRATION_TEMPERATURE_CALIBRATION : NAN);
|
||||
vcmd.param2 = NAN;
|
||||
vcmd.param3 = NAN;
|
||||
vcmd.param4 = NAN;
|
||||
vcmd.param5 = ((accel_calib || calib_all) ? vehicle_command_s::PREFLIGHT_CALIBRATION_TEMPERATURE_CALIBRATION : (double)NAN);
|
||||
vcmd.param5 = ((accel_calib
|
||||
|| calib_all) ? vehicle_command_s::PREFLIGHT_CALIBRATION_TEMPERATURE_CALIBRATION : (double)NAN);
|
||||
vcmd.param6 = (double)NAN;
|
||||
vcmd.param7 = (float)((baro_calib || calib_all) ? vehicle_command_s::PREFLIGHT_CALIBRATION_TEMPERATURE_CALIBRATION : NAN);
|
||||
vcmd.param7 = (float)((baro_calib
|
||||
|| calib_all) ? vehicle_command_s::PREFLIGHT_CALIBRATION_TEMPERATURE_CALIBRATION : NAN);
|
||||
vcmd.command = vehicle_command_s::VEHICLE_CMD_PREFLIGHT_CALIBRATION;
|
||||
|
||||
uORB::PublicationQueued<vehicle_command_s> vcmd_pub{ORB_ID(vehicle_command)};
|
||||
@@ -286,6 +263,32 @@ int SendEvent::custom_command(int argc, char *argv[])
|
||||
return 0;
|
||||
}
|
||||
|
||||
int SendEvent::print_usage(const char *reason)
|
||||
{
|
||||
if (reason) {
|
||||
printf("%s\n\n", reason);
|
||||
}
|
||||
|
||||
PRINT_MODULE_DESCRIPTION(
|
||||
R"DESCR_STR(
|
||||
### Description
|
||||
Background process running periodically on the LP work queue to perform housekeeping tasks.
|
||||
It is currently only responsible for temperature calibration and tone alarm on RC Loss.
|
||||
|
||||
The tasks can be started via CLI or uORB topics (vehicle_command from MAVLink, etc.).
|
||||
)DESCR_STR");
|
||||
|
||||
PRINT_MODULE_USAGE_NAME("send_event", "system");
|
||||
PRINT_MODULE_USAGE_COMMAND_DESCR("start", "Start the background task");
|
||||
PRINT_MODULE_USAGE_COMMAND_DESCR("temperature_calibration", "Run temperature calibration process");
|
||||
PRINT_MODULE_USAGE_PARAM_FLAG('g', "calibrate the gyro", true);
|
||||
PRINT_MODULE_USAGE_PARAM_FLAG('a', "calibrate the accel", true);
|
||||
PRINT_MODULE_USAGE_PARAM_FLAG('b', "calibrate the baro (if none of these is given, all will be calibrated)", true);
|
||||
PRINT_MODULE_USAGE_DEFAULT_COMMANDS();
|
||||
|
||||
return 0;
|
||||
}
|
||||
|
||||
int send_event_main(int argc, char *argv[])
|
||||
{
|
||||
return SendEvent::main(argc, argv);
|
||||
|
||||
@@ -40,13 +40,6 @@ using math::constrain;
|
||||
using math::gradual;
|
||||
using math::radians;
|
||||
|
||||
/**
|
||||
* Fixedwing attitude control app start / stop handling function
|
||||
*
|
||||
* @ingroup apps
|
||||
*/
|
||||
extern "C" __EXPORT int fw_att_control_main(int argc, char *argv[]);
|
||||
|
||||
FixedwingAttitudeControl::FixedwingAttitudeControl() :
|
||||
ModuleParams(nullptr),
|
||||
WorkItem(MODULE_NAME, px4::wq_configurations::att_pos_ctrl),
|
||||
@@ -762,6 +755,13 @@ int FixedwingAttitudeControl::custom_command(int argc, char *argv[])
|
||||
return print_usage("unknown command");
|
||||
}
|
||||
|
||||
int FixedwingAttitudeControl::print_status()
|
||||
{
|
||||
PX4_INFO("Running");
|
||||
perf_print_counter(_loop_perf);
|
||||
return 0;
|
||||
}
|
||||
|
||||
int FixedwingAttitudeControl::print_usage(const char *reason)
|
||||
{
|
||||
if (reason) {
|
||||
@@ -776,24 +776,13 @@ fw_att_control is the fixed wing attitude controller.
|
||||
)DESCR_STR");
|
||||
|
||||
PRINT_MODULE_USAGE_COMMAND("start");
|
||||
|
||||
PRINT_MODULE_USAGE_NAME("fw_att_control", "controller");
|
||||
|
||||
PRINT_MODULE_USAGE_DEFAULT_COMMANDS();
|
||||
|
||||
return 0;
|
||||
}
|
||||
|
||||
int FixedwingAttitudeControl::print_status()
|
||||
{
|
||||
PX4_INFO("Running");
|
||||
|
||||
perf_print_counter(_loop_perf);
|
||||
|
||||
return 0;
|
||||
}
|
||||
|
||||
int fw_att_control_main(int argc, char *argv[])
|
||||
extern "C" __EXPORT int fw_att_control_main(int argc, char *argv[])
|
||||
{
|
||||
return FixedwingAttitudeControl::main(argc, argv);
|
||||
}
|
||||
|
||||
@@ -33,8 +33,6 @@
|
||||
|
||||
#include "FixedwingPositionControl.hpp"
|
||||
|
||||
extern "C" __EXPORT int fw_pos_control_l1_main(int argc, char *argv[]);
|
||||
|
||||
FixedwingPositionControl::FixedwingPositionControl() :
|
||||
ModuleParams(nullptr),
|
||||
WorkItem(MODULE_NAME, px4::wq_configurations::att_pos_ctrl),
|
||||
@@ -1972,6 +1970,13 @@ int FixedwingPositionControl::custom_command(int argc, char *argv[])
|
||||
return print_usage("unknown command");
|
||||
}
|
||||
|
||||
int FixedwingPositionControl::print_status()
|
||||
{
|
||||
PX4_INFO("Running");
|
||||
perf_print_counter(_loop_perf);
|
||||
return 0;
|
||||
}
|
||||
|
||||
int FixedwingPositionControl::print_usage(const char *reason)
|
||||
{
|
||||
if (reason) {
|
||||
@@ -1993,16 +1998,7 @@ fw_pos_control_l1 is the fixed wing position controller.
|
||||
return 0;
|
||||
}
|
||||
|
||||
int FixedwingPositionControl::print_status()
|
||||
{
|
||||
PX4_INFO("Running");
|
||||
|
||||
perf_print_counter(_loop_perf);
|
||||
|
||||
return 0;
|
||||
}
|
||||
|
||||
int fw_pos_control_l1_main(int argc, char *argv[])
|
||||
extern "C" __EXPORT int fw_pos_control_l1_main(int argc, char *argv[])
|
||||
{
|
||||
return FixedwingPositionControl::main(argc, argv);
|
||||
}
|
||||
|
||||
@@ -953,6 +953,84 @@ Replay::custom_command(int argc, char *argv[])
|
||||
return print_usage("unknown command");
|
||||
}
|
||||
|
||||
int
|
||||
Replay::task_spawn(int argc, char *argv[])
|
||||
{
|
||||
// check if a log file was found
|
||||
if (!isSetup()) {
|
||||
if (argc > 0 && strncmp(argv[0], "try", 3) == 0) {
|
||||
return 0;
|
||||
}
|
||||
|
||||
PX4_ERR("no log file given (via env variable %s)", replay::ENV_FILENAME);
|
||||
return -1;
|
||||
}
|
||||
|
||||
_task_id = px4_task_spawn_cmd("replay",
|
||||
SCHED_DEFAULT,
|
||||
SCHED_PRIORITY_MAX - 5,
|
||||
4000,
|
||||
(px4_main_t)&run_trampoline,
|
||||
(char *const *)argv);
|
||||
|
||||
if (_task_id < 0) {
|
||||
_task_id = -1;
|
||||
return -errno;
|
||||
}
|
||||
|
||||
return 0;
|
||||
}
|
||||
|
||||
int
|
||||
Replay::applyParams(bool quiet)
|
||||
{
|
||||
if (!isSetup()) {
|
||||
if (quiet) {
|
||||
return 0;
|
||||
}
|
||||
|
||||
PX4_ERR("no log file given (via env variable %s)", replay::ENV_FILENAME);
|
||||
return -1;
|
||||
}
|
||||
|
||||
int ret = 0;
|
||||
Replay *r = new Replay();
|
||||
|
||||
if (r == nullptr) {
|
||||
PX4_ERR("alloc failed");
|
||||
return -ENOMEM;
|
||||
}
|
||||
|
||||
ifstream replay_file(_replay_file, ios::in | ios::binary);
|
||||
|
||||
if (!r->readDefinitionsAndApplyParams(replay_file)) {
|
||||
ret = -1;
|
||||
}
|
||||
|
||||
delete r;
|
||||
|
||||
return ret;
|
||||
}
|
||||
|
||||
Replay *
|
||||
Replay::instantiate(int argc, char *argv[])
|
||||
{
|
||||
// check the replay mode
|
||||
const char *replay_mode = getenv(replay::ENV_MODE);
|
||||
|
||||
Replay *instance = nullptr;
|
||||
|
||||
if (replay_mode && strcmp(replay_mode, "ekf2") == 0) {
|
||||
PX4_INFO("Ekf2 replay mode");
|
||||
instance = new ReplayEkf2();
|
||||
|
||||
} else {
|
||||
instance = new Replay();
|
||||
}
|
||||
|
||||
return instance;
|
||||
}
|
||||
|
||||
int
|
||||
Replay::print_usage(const char *reason)
|
||||
{
|
||||
@@ -989,79 +1067,4 @@ page.
|
||||
return 0;
|
||||
}
|
||||
|
||||
int
|
||||
Replay::task_spawn(int argc, char *argv[])
|
||||
{
|
||||
// check if a log file was found
|
||||
if (!isSetup()) {
|
||||
if (argc > 0 && strncmp(argv[0], "try", 3)==0) {
|
||||
return 0;
|
||||
}
|
||||
PX4_ERR("no log file given (via env variable %s)", replay::ENV_FILENAME);
|
||||
return -1;
|
||||
}
|
||||
|
||||
_task_id = px4_task_spawn_cmd("replay",
|
||||
SCHED_DEFAULT,
|
||||
SCHED_PRIORITY_MAX - 5,
|
||||
4000,
|
||||
(px4_main_t)&run_trampoline,
|
||||
(char *const *)argv);
|
||||
|
||||
if (_task_id < 0) {
|
||||
_task_id = -1;
|
||||
return -errno;
|
||||
}
|
||||
|
||||
return 0;
|
||||
}
|
||||
|
||||
int
|
||||
Replay::applyParams(bool quiet)
|
||||
{
|
||||
if (!isSetup()) {
|
||||
if (quiet) {
|
||||
return 0;
|
||||
}
|
||||
PX4_ERR("no log file given (via env variable %s)", replay::ENV_FILENAME);
|
||||
return -1;
|
||||
}
|
||||
|
||||
int ret = 0;
|
||||
Replay *r = new Replay();
|
||||
|
||||
if (r == nullptr) {
|
||||
PX4_ERR("alloc failed");
|
||||
return -ENOMEM;
|
||||
}
|
||||
|
||||
ifstream replay_file(_replay_file, ios::in | ios::binary);
|
||||
|
||||
if (!r->readDefinitionsAndApplyParams(replay_file)) {
|
||||
ret = -1;
|
||||
}
|
||||
|
||||
delete r;
|
||||
|
||||
return ret;
|
||||
}
|
||||
|
||||
Replay *
|
||||
Replay::instantiate(int argc, char *argv[])
|
||||
{
|
||||
// check the replay mode
|
||||
const char *replay_mode = getenv(replay::ENV_MODE);
|
||||
|
||||
Replay *instance = nullptr;
|
||||
if (replay_mode && strcmp(replay_mode, "ekf2") == 0) {
|
||||
PX4_INFO("Ekf2 replay mode");
|
||||
instance = new ReplayEkf2();
|
||||
|
||||
} else {
|
||||
instance = new Replay();
|
||||
}
|
||||
|
||||
return instance;
|
||||
}
|
||||
|
||||
} //namespace px4
|
||||
|
||||
@@ -477,6 +477,14 @@ VtolAttitudeControl::custom_command(int argc, char *argv[])
|
||||
return print_usage("unknown command");
|
||||
}
|
||||
|
||||
int
|
||||
VtolAttitudeControl::print_status()
|
||||
{
|
||||
PX4_INFO("Running");
|
||||
perf_print_counter(_loop_perf);
|
||||
return PX4_OK;
|
||||
}
|
||||
|
||||
int
|
||||
VtolAttitudeControl::print_usage(const char *reason)
|
||||
{
|
||||
@@ -491,24 +499,12 @@ fw_att_control is the fixed wing attitude controller.
|
||||
)DESCR_STR");
|
||||
|
||||
PRINT_MODULE_USAGE_COMMAND("start");
|
||||
|
||||
PRINT_MODULE_USAGE_NAME("vtol_att_control", "controller");
|
||||
|
||||
PRINT_MODULE_USAGE_DEFAULT_COMMANDS();
|
||||
|
||||
return 0;
|
||||
}
|
||||
|
||||
int
|
||||
VtolAttitudeControl::print_status()
|
||||
{
|
||||
PX4_INFO("Running");
|
||||
|
||||
perf_print_counter(_loop_perf);
|
||||
|
||||
return PX4_OK;
|
||||
}
|
||||
|
||||
int vtol_att_control_main(int argc, char *argv[])
|
||||
{
|
||||
return VtolAttitudeControl::main(argc, argv);
|
||||
|
||||
@@ -46,28 +46,6 @@ extern "C" {
|
||||
__EXPORT int dmesg_main(int argc, char *argv[]);
|
||||
}
|
||||
|
||||
static void
|
||||
usage()
|
||||
{
|
||||
|
||||
PRINT_MODULE_DESCRIPTION(
|
||||
R"DESCR_STR(
|
||||
### Description
|
||||
|
||||
Command-line tool to show bootup console messages.
|
||||
Note that output from NuttX's work queues and syslog are not captured.
|
||||
|
||||
### Examples
|
||||
|
||||
Keep printing all messages in the background:
|
||||
$ dmesg -f &
|
||||
)DESCR_STR");
|
||||
|
||||
PRINT_MODULE_USAGE_NAME("dmesg", "system");
|
||||
PRINT_MODULE_USAGE_PARAM_FLAG('f', "Follow: wait for new messages", true);
|
||||
|
||||
}
|
||||
|
||||
int
|
||||
dmesg_main(int argc, char *argv[])
|
||||
{
|
||||
@@ -93,3 +71,25 @@ dmesg_main(int argc, char *argv[])
|
||||
|
||||
return 0;
|
||||
}
|
||||
|
||||
static void
|
||||
usage()
|
||||
{
|
||||
|
||||
PRINT_MODULE_DESCRIPTION(
|
||||
R"DESCR_STR(
|
||||
### Description
|
||||
|
||||
Command-line tool to show bootup console messages.
|
||||
Note that output from NuttX's work queues and syslog are not captured.
|
||||
|
||||
### Examples
|
||||
|
||||
Keep printing all messages in the background:
|
||||
$ dmesg -f &
|
||||
)DESCR_STR");
|
||||
|
||||
PRINT_MODULE_USAGE_NAME("dmesg", "system");
|
||||
PRINT_MODULE_USAGE_PARAM_FLAG('f', "Follow: wait for new messages", true);
|
||||
|
||||
}
|
||||
|
||||
Reference in New Issue
Block a user