PX4 Firmware
PX4 Autopilot Software http://px4.io
|
Commander helper functions definitions. More...
#include <uORB/uORB.h>
#include <uORB/topics/vehicle_status.h>
#include <uORB/topics/actuator_armed.h>
#include <uORB/topics/vehicle_control_mode.h>
#include <drivers/drv_led.h>
#include <drivers/drv_board_led.h>
Go to the source code of this file.
Functions | |
bool | is_multirotor (const struct vehicle_status_s *current_status) |
bool | is_rotary_wing (const struct vehicle_status_s *current_status) |
bool | is_vtol (const struct vehicle_status_s *current_status) |
bool | is_vtol_tailsitter (const struct vehicle_status_s *current_status) |
bool | is_fixed_wing (const struct vehicle_status_s *current_status) |
bool | is_ground_rover (const struct vehicle_status_s *current_status) |
int | buzzer_init (void) |
void | buzzer_deinit (void) |
void | set_tune_override (int tune) |
void | set_tune (int tune) |
void | tune_home_set (bool use_buzzer) |
void | tune_mission_ok (bool use_buzzer) |
void | tune_mission_fail (bool use_buzzer) |
void | tune_positive (bool use_buzzer) |
Blink green LED and play positive tune (if use_buzzer == true). More... | |
void | tune_neutral (bool use_buzzer) |
Blink white LED and play neutral tune (if use_buzzer == true). More... | |
void | tune_negative (bool use_buzzer) |
Blink red LED and play negative tune (if use_buzzer == true). More... | |
void | tune_failsafe (bool use_buzzer) |
int | blink_msg_state () |
int | led_init (void) |
void | led_deinit (void) |
int | led_toggle (int led) |
int | led_on (int led) |
int | led_off (int led) |
void | rgbled_set_color_and_mode (uint8_t color, uint8_t mode) |
set the LED color & mode More... | |
void | rgbled_set_color_and_mode (uint8_t color, uint8_t mode, uint8_t blinks, uint8_t prio) |
Commander helper functions definitions.
Definition in file commander_helper.h.
int blink_msg_state | ( | ) |
Definition at line 274 of file commander_helper.cpp.
References blink_msg_end, and hrt_absolute_time().
Referenced by Commander::run().
void buzzer_deinit | ( | void | ) |
Definition at line 155 of file commander_helper.cpp.
References orb_unadvertise(), and tune_control_pub.
Referenced by Commander::run().
int buzzer_init | ( | void | ) |
Definition at line 141 of file commander_helper.cpp.
References orb_advertise_queue(), ORB_ID, TONE_ARMING_WARNING_TUNE, TONE_BATTERY_WARNING_FAST_TUNE, TONE_BATTERY_WARNING_SLOW_TUNE, TONE_HOME_SET, TONE_NOTIFY_NEGATIVE_TUNE, TONE_NOTIFY_NEUTRAL_TUNE, TONE_NOTIFY_POSITIVE_TUNE, TONE_SINGLE_BEEP_TUNE, tune_control, tune_control_pub, and tune_durations.
Referenced by Commander::run().
bool is_fixed_wing | ( | const struct vehicle_status_s * | current_status | ) |
Definition at line 119 of file commander_helper.cpp.
References vehicle_status_s::system_type, and VEHICLE_TYPE_FIXED_WING.
Referenced by Commander::run(), Ekf2::Run(), EstimatorInterface::set_is_fixed_wing(), and FixedwingAttitudeControl::vehicle_manual_poll().
bool is_ground_rover | ( | const struct vehicle_status_s * | current_status | ) |
Definition at line 124 of file commander_helper.cpp.
References vehicle_status_s::system_type, and VEHICLE_TYPE_GROUND_ROVER.
Referenced by Commander::handle_command(), and Commander::run().
bool is_multirotor | ( | const struct vehicle_status_s * | current_status | ) |
Definition at line 88 of file commander_helper.cpp.
References vehicle_status_s::system_type, VEHICLE_TYPE_HEXAROTOR, VEHICLE_TYPE_OCTOROTOR, VEHICLE_TYPE_QUADROTOR, and VEHICLE_TYPE_TRICOPTER.
Referenced by is_rotary_wing().
bool is_rotary_wing | ( | const struct vehicle_status_s * | current_status | ) |
Definition at line 96 of file commander_helper.cpp.
References is_multirotor(), vehicle_status_s::system_type, VEHICLE_TYPE_COAXIAL, and VEHICLE_TYPE_HELICOPTER.
Referenced by Commander::run().
bool is_vtol | ( | const struct vehicle_status_s * | current_status | ) |
Definition at line 102 of file commander_helper.cpp.
References vehicle_status_s::system_type, VEHICLE_TYPE_VTOL_DUOROTOR, VEHICLE_TYPE_VTOL_QUADROTOR, VEHICLE_TYPE_VTOL_RESERVED2, VEHICLE_TYPE_VTOL_RESERVED3, VEHICLE_TYPE_VTOL_RESERVED4, VEHICLE_TYPE_VTOL_RESERVED5, and VEHICLE_TYPE_VTOL_TILTROTOR.
Referenced by Commander::run().
bool is_vtol_tailsitter | ( | const struct vehicle_status_s * | current_status | ) |
Definition at line 113 of file commander_helper.cpp.
References vehicle_status_s::system_type, VEHICLE_TYPE_VTOL_DUOROTOR, and VEHICLE_TYPE_VTOL_QUADROTOR.
Referenced by Commander::run().
void led_deinit | ( | void | ) |
Definition at line 327 of file commander_helper.cpp.
References h_leds, led_control_pub, and orb_unadvertise().
Referenced by Commander::run().
int led_init | ( | void | ) |
Definition at line 288 of file commander_helper.cpp.
int led_off | ( | int | led | ) |
Definition at line 343 of file commander_helper.cpp.
int led_on | ( | int | led | ) |
Definition at line 338 of file commander_helper.cpp.
int led_toggle | ( | int | led | ) |
Definition at line 333 of file commander_helper.cpp.
void rgbled_set_color_and_mode | ( | uint8_t | color, |
uint8_t | mode | ||
) |
set the LED color & mode
color |
mode |
Definition at line 358 of file commander_helper.cpp.
References rgbled_set_color_and_mode().
void rgbled_set_color_and_mode | ( | uint8_t | color, |
uint8_t | mode, | ||
uint8_t | blinks, | ||
uint8_t | prio | ||
) |
Definition at line 348 of file commander_helper.cpp.
References led_control_s::color, hrt_absolute_time(), led_control, led_control_pub, led_control_s::mode, led_control_s::num_blinks, ORB_ID, orb_publish(), led_control_s::priority, and led_control_s::timestamp.
Referenced by calibrate_from_orientation(), control_status_leds(), rgbled_set_color_and_mode(), Commander::run(), tune_failsafe(), tune_home_set(), tune_mission_fail(), tune_mission_ok(), tune_negative(), tune_neutral(), and tune_positive().
void set_tune | ( | int | tune | ) |
Definition at line 169 of file commander_helper.cpp.
References hrt_absolute_time(), ORB_ID, orb_publish(), tune_control_s::timestamp, tune_control, tune_control_pub, tune_current, tune_durations, tune_end, tune_control_s::tune_id, tune_control_s::tune_override, and tune_control_s::volume.
Referenced by calibrate_from_orientation(), mag_calibration_worker(), Commander::run(), tune_failsafe(), tune_home_set(), tune_mission_fail(), tune_mission_ok(), tune_negative(), tune_neutral(), and tune_positive().
void set_tune_override | ( | int | tune | ) |
Definition at line 160 of file commander_helper.cpp.
References hrt_absolute_time(), ORB_ID, orb_publish(), tune_control_s::timestamp, tune_control, tune_control_pub, tune_control_s::tune_id, tune_control_s::tune_override, and tune_control_s::volume.
Referenced by Commander::run().
void tune_failsafe | ( | bool | use_buzzer | ) |
Definition at line 264 of file commander_helper.cpp.
References blink_msg_end, BLINK_MSG_TIME, hrt_absolute_time(), rgbled_set_color_and_mode(), set_tune(), and TONE_BATTERY_WARNING_FAST_TUNE.
Referenced by Commander::run().
void tune_home_set | ( | bool | use_buzzer | ) |
Definition at line 195 of file commander_helper.cpp.
References blink_msg_end, BLINK_MSG_TIME, hrt_absolute_time(), rgbled_set_color_and_mode(), set_tune(), and TONE_HOME_SET.
Referenced by Commander::set_home_position().
void tune_mission_fail | ( | bool | use_buzzer | ) |
Definition at line 215 of file commander_helper.cpp.
References blink_msg_end, BLINK_MSG_TIME, hrt_absolute_time(), rgbled_set_color_and_mode(), set_tune(), and TONE_NOTIFY_NEGATIVE_TUNE.
Referenced by Commander::run().
void tune_mission_ok | ( | bool | use_buzzer | ) |
Definition at line 205 of file commander_helper.cpp.
References blink_msg_end, BLINK_MSG_TIME, hrt_absolute_time(), rgbled_set_color_and_mode(), set_tune(), and TONE_NOTIFY_NEUTRAL_TUNE.
Referenced by Commander::run().
void tune_negative | ( | bool | use_buzzer | ) |
Blink red LED and play negative tune (if use_buzzer == true).
Definition at line 254 of file commander_helper.cpp.
References blink_msg_end, BLINK_MSG_TIME, hrt_absolute_time(), rgbled_set_color_and_mode(), set_tune(), and TONE_NOTIFY_NEGATIVE_TUNE.
Referenced by answer_command(), arm_disarm(), calibrate_answer_command(), commander_low_prio_loop(), print_reject_arm(), print_reject_mode(), and Commander::run().
void tune_neutral | ( | bool | use_buzzer | ) |
Blink white LED and play neutral tune (if use_buzzer == true).
Definition at line 241 of file commander_helper.cpp.
References blink_msg_end, BLINK_MSG_TIME, hrt_absolute_time(), rgbled_set_color_and_mode(), set_tune(), and TONE_NOTIFY_NEUTRAL_TUNE.
Referenced by do_airspeed_calibration(), and Commander::run().
void tune_positive | ( | bool | use_buzzer | ) |
Blink green LED and play positive tune (if use_buzzer == true).
Definition at line 228 of file commander_helper.cpp.
References blink_msg_end, BLINK_MSG_TIME, hrt_absolute_time(), rgbled_set_color_and_mode(), set_tune(), and TONE_NOTIFY_POSITIVE_TUNE.
Referenced by calibrate_answer_command(), commander_low_prio_loop(), and Commander::run().