mirror of
https://github.com/PX4/PX4-Autopilot.git
synced 2026-05-24 15:40:31 +08:00
voxl_esc: Added GPIO control feature
Build all targets / Scan for Board Targets (push) Waiting to run
Build all targets / Build Group [${{ matrix.group }}] (push) Blocked by required conditions
Build all targets / Upload Artifacts to S3 (push) Blocked by required conditions
Build all targets / Create Release and Upload Artifacts (push) Blocked by required conditions
Checks / build (NO_NINJA_BUILD=1 px4_fmu-v5_default) (push) Waiting to run
Checks / build (NO_NINJA_BUILD=1 px4_sitl_default) (push) Waiting to run
Checks / build (check_format) (push) Waiting to run
Checks / build (check_newlines) (push) Waiting to run
Checks / build (module_documentation) (push) Waiting to run
Checks / build (px4_fmu-v2_default stack_check) (push) Waiting to run
Checks / build (px4_sitl_allyes) (push) Waiting to run
Checks / build (shellcheck_all) (push) Waiting to run
Checks / build (tests) (push) Waiting to run
Checks / build (tests_coverage) (push) Waiting to run
Checks / build (validate_module_configs) (push) Waiting to run
Clang Tidy / build (push) Waiting to run
MacOS build / build (px4_fmu-v5_default) (push) Waiting to run
MacOS build / build (px4_sitl) (push) Waiting to run
Ubuntu environment build / Build and Test (ubuntu:22.04) (push) Waiting to run
Ubuntu environment build / Build and Test (ubuntu:24.04) (push) Waiting to run
Container build / Build and Push Container (push) Waiting to run
EKF Update Change Indicator / unit_tests (push) Waiting to run
Failsafe Simulator Build / build (failsafe_web) (push) Waiting to run
FLASH usage analysis / Analyzing px4_fmu-v5x (push) Waiting to run
FLASH usage analysis / Analyzing px4_fmu-v6x (push) Waiting to run
FLASH usage analysis / Publish Results (push) Blocked by required conditions
MAVROS Mission Tests / build (map[mission:MC_mission_box vehicle:iris]) (push) Waiting to run
MAVROS Mission Tests / build (map[mission:rover_mission_1 vehicle:rover]) (push) Waiting to run
MAVROS Offboard Tests / build (map[test_file:mavros_posix_tests_offboard_posctl.test vehicle:iris]) (push) Waiting to run
Nuttx Target with extra env config / build (px4_fmu-v5_default) (push) Waiting to run
Python CI Checks / build (push) Waiting to run
ROS Translation Node Tests / Build and test (map[ros_version:humble ubuntu:jammy]) (push) Waiting to run
ROS Translation Node Tests / Build and test (map[ros_version:jazzy ubuntu:noble]) (push) Waiting to run
SITL Tests / Testing PX4 tailsitter (push) Waiting to run
SITL Tests / Testing PX4 iris (push) Waiting to run
SITL Tests / Testing PX4 standard_vtol (push) Waiting to run
Build all targets / Scan for Board Targets (push) Waiting to run
Build all targets / Build Group [${{ matrix.group }}] (push) Blocked by required conditions
Build all targets / Upload Artifacts to S3 (push) Blocked by required conditions
Build all targets / Create Release and Upload Artifacts (push) Blocked by required conditions
Checks / build (NO_NINJA_BUILD=1 px4_fmu-v5_default) (push) Waiting to run
Checks / build (NO_NINJA_BUILD=1 px4_sitl_default) (push) Waiting to run
Checks / build (check_format) (push) Waiting to run
Checks / build (check_newlines) (push) Waiting to run
Checks / build (module_documentation) (push) Waiting to run
Checks / build (px4_fmu-v2_default stack_check) (push) Waiting to run
Checks / build (px4_sitl_allyes) (push) Waiting to run
Checks / build (shellcheck_all) (push) Waiting to run
Checks / build (tests) (push) Waiting to run
Checks / build (tests_coverage) (push) Waiting to run
Checks / build (validate_module_configs) (push) Waiting to run
Clang Tidy / build (push) Waiting to run
MacOS build / build (px4_fmu-v5_default) (push) Waiting to run
MacOS build / build (px4_sitl) (push) Waiting to run
Ubuntu environment build / Build and Test (ubuntu:22.04) (push) Waiting to run
Ubuntu environment build / Build and Test (ubuntu:24.04) (push) Waiting to run
Container build / Build and Push Container (push) Waiting to run
EKF Update Change Indicator / unit_tests (push) Waiting to run
Failsafe Simulator Build / build (failsafe_web) (push) Waiting to run
FLASH usage analysis / Analyzing px4_fmu-v5x (push) Waiting to run
FLASH usage analysis / Analyzing px4_fmu-v6x (push) Waiting to run
FLASH usage analysis / Publish Results (push) Blocked by required conditions
MAVROS Mission Tests / build (map[mission:MC_mission_box vehicle:iris]) (push) Waiting to run
MAVROS Mission Tests / build (map[mission:rover_mission_1 vehicle:rover]) (push) Waiting to run
MAVROS Offboard Tests / build (map[test_file:mavros_posix_tests_offboard_posctl.test vehicle:iris]) (push) Waiting to run
Nuttx Target with extra env config / build (px4_fmu-v5_default) (push) Waiting to run
Python CI Checks / build (push) Waiting to run
ROS Translation Node Tests / Build and test (map[ros_version:humble ubuntu:jammy]) (push) Waiting to run
ROS Translation Node Tests / Build and test (map[ros_version:jazzy ubuntu:noble]) (push) Waiting to run
SITL Tests / Testing PX4 tailsitter (push) Waiting to run
SITL Tests / Testing PX4 iris (push) Waiting to run
SITL Tests / Testing PX4 standard_vtol (push) Waiting to run
voxl_esc: Removed obsolete modal_io_data UORB topic
This commit is contained in:
committed by
Daniel Agar
parent
73dbecadf1
commit
98ceb0ce79
@@ -1,8 +0,0 @@
|
||||
uint64 timestamp # time since system start (microseconds)
|
||||
|
||||
uint8 len # length of data
|
||||
uint32 MAX_BUFLEN = 128
|
||||
|
||||
uint8[128] data # data
|
||||
|
||||
# TOPICS voxl2_io_data
|
||||
@@ -48,7 +48,6 @@ set(msg_files
|
||||
AirspeedValidated.msg
|
||||
AirspeedWind.msg
|
||||
AutotuneAttitudeControlStatus.msg
|
||||
Buffer128.msg
|
||||
ButtonEvent.msg
|
||||
CameraCapture.msg
|
||||
CameraStatus.msg
|
||||
|
||||
File diff suppressed because it is too large
Load Diff
@@ -49,7 +49,6 @@
|
||||
#include <uORB/topics/led_control.h>
|
||||
#include <uORB/topics/esc_status.h>
|
||||
#include <uORB/topics/actuator_test.h>
|
||||
#include <uORB/topics/buffer128.h>
|
||||
|
||||
#include <px4_platform_common/Serial.hpp>
|
||||
|
||||
@@ -129,17 +128,24 @@ private:
|
||||
static constexpr uint32_t VOXL_ESC_MODE_TURTLE_AUX1 = 1;
|
||||
static constexpr uint32_t VOXL_ESC_MODE_TURTLE_AUX2 = 2;
|
||||
|
||||
static constexpr uint16_t VOXL_ESC_EXT_RPM =
|
||||
39; // minimum firmware version for extended RPM command support
|
||||
static constexpr uint16_t VOXL_ESC_RPM_MAX = INT16_MAX -
|
||||
1; // 32K, Limit max standard range RPM to prevent overflow (rpm packet packing function accepts int32_t)
|
||||
static constexpr uint16_t VOXL_ESC_RPM_MAX_EXT = UINT16_MAX -
|
||||
5; // 65K, Limit max extended range RPM to prevent overflow (rpm packet packing function accepts int32_t)
|
||||
// minimum firmware version for extended RPM command support
|
||||
static constexpr uint16_t VOXL_ESC_EXT_RPM = 39;
|
||||
// 32K, Limit max standard range RPM to prevent overflow (rpm packet packing function accepts int32_t)
|
||||
static constexpr uint16_t VOXL_ESC_RPM_MAX = INT16_MAX - 1;
|
||||
// 65K, Limit max extended range RPM to prevent overflow (rpm packet packing function accepts int32_t)
|
||||
static constexpr uint16_t VOXL_ESC_RPM_MAX_EXT = UINT16_MAX - 5;
|
||||
|
||||
static constexpr uint16_t VOXL_ESC_NUM_INIT_RETRIES = 3;
|
||||
|
||||
//static constexpr uint16_t max_pwm(uint16_t pwm) { return math::min(pwm, VOXL_ESC_PWM_MAX); }
|
||||
//static constexpr uint16_t max_rpm(uint16_t rpm) { return math::min(rpm, VOXL_ESC_RPM_MAX); }
|
||||
static constexpr float VOXL_ESC_GPIO_CTL_DISABLED_SETPOINT = -0.1f;
|
||||
static constexpr float VOXL_ESC_GPIO_CTL_THRESHOLD = 0.0f;
|
||||
|
||||
static constexpr uint32_t VOXL_ESC_GPIO_CTL_AUX1 = 1;
|
||||
static constexpr uint32_t VOXL_ESC_GPIO_CTL_AUX2 = 2;
|
||||
static constexpr uint32_t VOXL_ESC_GPIO_CTL_AUX3 = 3;
|
||||
static constexpr uint32_t VOXL_ESC_GPIO_CTL_AUX4 = 4;
|
||||
static constexpr uint32_t VOXL_ESC_GPIO_CTL_AUX5 = 5;
|
||||
static constexpr uint32_t VOXL_ESC_GPIO_CTL_AUX6 = 6;
|
||||
|
||||
Serial _uart_port{};
|
||||
|
||||
@@ -161,6 +167,7 @@ private:
|
||||
int32_t publish_battery_status{0};
|
||||
int32_t esc_warn_temp_threshold{0};
|
||||
int32_t esc_over_temp_threshold{0};
|
||||
int32_t gpio_ctl_channel{0};
|
||||
} voxl_esc_params_t;
|
||||
|
||||
struct EscChan {
|
||||
@@ -205,7 +212,6 @@ private:
|
||||
uORB::Subscription _parameter_update_sub{ORB_ID(parameter_update)};
|
||||
uORB::Subscription _actuator_test_sub{ORB_ID(actuator_test)};
|
||||
uORB::Subscription _led_update_sub{ORB_ID(led_control)};
|
||||
uORB::Subscription _voxl2_io_data_sub{ORB_ID(voxl2_io_data)};
|
||||
|
||||
uORB::Publication<actuator_outputs_s> _outputs_debug_pub{ORB_ID(actuator_outputs_debug)};
|
||||
uORB::Publication<esc_status_s> _esc_status_pub{ORB_ID(esc_status)};
|
||||
@@ -224,6 +230,11 @@ private:
|
||||
int32_t _rpm_fullscale{0};
|
||||
manual_control_setpoint_s _manual_control_setpoint{};
|
||||
|
||||
int32_t _gpio_write_counter{0};
|
||||
bool _gpio_ctl_en{false};
|
||||
bool _gpio_ctl_high{true};
|
||||
bool _prev_gpio_ctl_high{true};
|
||||
|
||||
uint16_t _cmd_id{0};
|
||||
Command _current_cmd;
|
||||
px4::atomic<Command *> _pending_cmd{nullptr};
|
||||
|
||||
@@ -262,3 +262,17 @@ PARAM_DEFINE_INT32(VOXL_ESC_T_WARN, 0);
|
||||
* @max 200
|
||||
*/
|
||||
PARAM_DEFINE_INT32(VOXL_ESC_T_OVER, 0);
|
||||
|
||||
|
||||
/**
|
||||
* GPIO Control Channel
|
||||
*
|
||||
*
|
||||
* @reboot_required true
|
||||
*
|
||||
* @group VOXL ESC
|
||||
* @value 0 - Disabled
|
||||
* @min 0
|
||||
* @max 6
|
||||
*/
|
||||
PARAM_DEFINE_INT32(VOXL_ESC_GPIO_CH, 0);
|
||||
|
||||
Reference in New Issue
Block a user