Compare commits

...

8 Commits

Author SHA1 Message Date
Daniel Agar f716224c45 uavcan: add UAVCAN_SUB_LOG param to enable/disable uavcan::protocol::debug::LogMessage subscription handling 2022-06-30 10:56:48 -04:00
Ryan Meagher f16ea921c2 drivers/barometer/invensense: fix icp10111 and icp10100
* fix icp so it compiles
* add icp10111 and icp10100 DEVTPYE
2022-06-29 21:22:10 -04:00
Martina Rivizzigno 55563eba49 MPC_SPOOLUP_TIME -> COM_SPOOLUP_TIME 2022-06-24 19:44:43 +02:00
Matthias Grob c8fb7a6990 fw/uuv control: remove duplicated comments, restyle initializers 2022-06-24 10:05:16 -05:00
Matthias Grob 78225f7b1f examples/fixedwing_control: use initializers instead of memset 2022-06-24 10:05:16 -05:00
Matthias Grob cfd4e64b02 uuv_pos_control: remove practically unused manual control subscription 2022-06-24 10:05:16 -05:00
Matthias Grob 3a239ff649 examples: remove empty fake_gyro 2022-06-24 10:05:16 -05:00
CUAVhonglang cfa8b451c7 cuav-nora: changed brick to compatible with cuav noraplus 2022-06-24 10:03:43 -05:00
27 changed files with 116 additions and 99 deletions
@@ -62,7 +62,7 @@ param set-default MPC_JERK_AUTO 4
param set-default MPC_LAND_SPEED 1
param set-default MPC_MAN_TILT_MAX 25
param set-default MPC_MAN_Y_MAX 40
param set-default MPC_SPOOLUP_TIME 1.5
param set-default COM_SPOOLUP_TIME 1.5
param set-default MPC_THR_HOVER 0.45
param set-default MPC_TILTMAX_AIR 25
param set-default MPC_TKO_RAMP_T 1.8
+2 -2
View File
@@ -118,8 +118,8 @@
#define GPIO_nPOWER_IN_CAN /* PG2 */ (GPIO_INPUT|GPIO_PULLUP|GPIO_PORTG|GPIO_PIN2)
#define GPIO_nPOWER_IN_C /* PG0 */ (GPIO_INPUT|GPIO_PULLUP|GPIO_PORTG|GPIO_PIN0)
#define GPIO_nVDD_BRICK1_VALID GPIO_nPOWER_IN_CAN /* Brick 1 is Chosen */
#define GPIO_nVDD_BRICK2_VALID GPIO_nPOWER_IN_ADC /* Brick 2 is Chosen */
#define GPIO_nVDD_BRICK1_VALID GPIO_nPOWER_IN_ADC /* Brick 1 is Chosen */
#define GPIO_nVDD_BRICK2_VALID GPIO_nPOWER_IN_CAN /* Brick 2 is Chosen */
#define GPIO_nVDD_USB_VALID GPIO_nPOWER_IN_C /* USB is Chosen */
#define GPIO_VDD_5V_HIPOWER_EN /* PD11 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_SET|GPIO_PORTD|GPIO_PIN11)
+3
View File
@@ -0,0 +1,3 @@
menu "Invensense"
rsource "*/Kconfig"
endmenu #Invensense
@@ -32,7 +32,7 @@
############################################################################
px4_add_module(
MODULE drivers__invensense__icp10100
MODULE drivers__barometer__invensense__icp10100
MAIN icp10100
COMPILE_FLAGS
SRCS
@@ -233,7 +233,6 @@ ICP10100::RunImpl()
float b = (_pcal[0] - a) * (s1 + c);
float _pressure_Pa = a + b / (c + _raw_p);
const hrt_abstime nowx = hrt_absolute_time();
float temperature = _temperature_C;
float pressure = _pressure_Pa;
@@ -0,0 +1,7 @@
menuconfig DRIVERS_BAROMETER_INVENSENSE_ICP10100
bool "icp10100"
default n
---help---
Enable support for icp10100
@@ -32,7 +32,7 @@
############################################################################
px4_add_module(
MODULE drivers__invensense__icp10111
MODULE drivers__barometer__invensense__icp10111
MAIN icp10111
COMPILE_FLAGS
SRCS
@@ -0,0 +1,6 @@
menuconfig DRIVERS_BAROMETER_INVENSENSE_ICP10111
bool "icp10100"
default n
---help---
Enable support for icp10111
+3
View File
@@ -213,6 +213,9 @@
#define DRV_FLOW_DEVTYPE_PX4FLOW 0xB5
#define DRV_FLOW_DEVTYPE_PAA3905 0xB6
#define DRV_BARO_DEVTYPE_ICP10100 0xC0
#define DRV_BARO_DEVTYPE_ICP10111 0xC1
#define DRV_DEVTYPE_UNUSED 0xff
#endif /* _DRV_SENSOR_H */
+12 -6
View File
@@ -508,6 +508,18 @@ UavcanNode::init(uavcan::NodeID node_id, UAVCAN_DRIVER::BusEvent &bus_events)
fill_node_info();
// log message subscription
int32_t uavcan_sub_log = 1;
param_get(param_find("UAVCAN_SUB_LOG"), &uavcan_sub_log);
if (uavcan_sub_log != 0) {
ret = _log_message_controller.init();
if (ret < 0) {
return ret;
}
}
ret = _beep_controller.init();
if (ret < 0) {
@@ -533,12 +545,6 @@ UavcanNode::init(uavcan::NodeID node_id, UAVCAN_DRIVER::BusEvent &bus_events)
return ret;
}
ret = _log_message_controller.init();
if (ret < 0) {
return ret;
}
ret = _rgbled_controller.init();
if (ret < 0) {
+12
View File
@@ -307,6 +307,18 @@ PARAM_DEFINE_INT32(UAVCAN_SUB_ICE, 0);
*/
PARAM_DEFINE_INT32(UAVCAN_SUB_IMU, 0);
/**
* subscription log message
*
* Enable UAVCAN log message subscription.
* uavcan::protocol::debug::LogMessage
*
* @boolean
* @reboot_required true
* @group UAVCAN
*/
PARAM_DEFINE_INT32(UAVCAN_SUB_LOG, 1);
/**
* subscription magnetometer
*
-5
View File
@@ -1,5 +0,0 @@
menuconfig EXAMPLES_FAKE_GYRO
bool "fake_gyro"
default n
---help---
Enable support for fake_gyro
+6 -17
View File
@@ -278,25 +278,14 @@ int fixedwing_control_thread_main(int argc, char *argv[])
* These structs contain the system state and things
* like attitude, position, the current waypoint, etc.
*/
struct vehicle_attitude_s att;
memset(&att, 0, sizeof(att));
struct vehicle_attitude_setpoint_s att_sp;
memset(&att_sp, 0, sizeof(att_sp));
struct vehicle_rates_setpoint_s rates_sp;
memset(&rates_sp, 0, sizeof(rates_sp));
struct vehicle_global_position_s global_pos;
memset(&global_pos, 0, sizeof(global_pos));
struct manual_control_setpoint_s manual_control_setpoint;
memset(&manual_control_setpoint, 0, sizeof(manual_control_setpoint));
struct vehicle_status_s vstatus;
memset(&vstatus, 0, sizeof(vstatus));
struct position_setpoint_s global_sp;
memset(&global_sp, 0, sizeof(global_sp));
vehicle_attitude_s att{};
vehicle_rates_setpoint_s rates_sp{};
manual_control_setpoint_s manual_control_setpoint{};
vehicle_status_s vstatus{};
position_setpoint_s global_sp{};
/* output structs - this is what is sent to the mixer */
struct actuator_controls_s actuators;
memset(&actuators, 0, sizeof(actuators));
actuator_controls_s actuators{};
/* publish actuator controls with zero values */
for (unsigned i = 0; i < actuator_controls_s::NUM_ACTUATOR_CONTROLS; i++) {
+9
View File
@@ -42,6 +42,15 @@
bool param_modify_on_import(bson_node_t node)
{
// migrate MPC_SPOOLUP_TIME -> COM_SPOOLUP_TIME (2020-12-03). This can be removed after the next release (current release=1.11)
if (node->type == BSON_DOUBLE) {
if (strcmp("MPC_SPOOLUP_TIME", node->name) == 0) {
strcpy(node->name, "COM_SPOOLUP_TIME");
PX4_INFO("param migrating MPC_SPOOLUP_TIME (removed) -> COM_SPOOLUP_TIME: value=%.3f", node->d);
return true;
}
}
// migrate COM_ARM_AUTH -> COM_ARM_AUTH_ID, COM_ARM_AUTH_MET and COM_ARM_AUTH_TO (2020-11-06). This can be removed after the next release (current release=1.11)
if (node->type == BSON_INT32) {
if (strcmp("COM_ARM_AUTH", node->name) == 0) {
+2 -2
View File
@@ -2721,8 +2721,8 @@ Commander::run()
if (_arm_state_machine.isArmed()) {
if (fd_status_flags.arm_escs) {
// 500ms is the PWM spoolup time. Within this timeframe controllers are not affecting actuator_outputs
if (hrt_elapsed_time(&_vehicle_status.armed_time) < 500_ms) {
// Checks have to pass within the spool up time
if (hrt_elapsed_time(&_vehicle_status.armed_time) < _param_com_spoolup_time.get() * 1_s) {
disarm(arm_disarm_reason_t::failure_detector);
mavlink_log_critical(&_mavlink_log_pub, "ESCs did not respond to arm request\t");
events::send(events::ID("commander_fd_escs_not_arming"), events::Log::Critical, "ESCs did not respond to arm request");
+3 -1
View File
@@ -258,7 +258,9 @@ private:
(ParamInt<px4::params::CBRK_VTOLARMING>) _param_cbrk_vtolarming,
(ParamInt<px4::params::COM_FLT_TIME_MAX>) _param_com_flt_time_max,
(ParamFloat<px4::params::COM_WIND_MAX>) _param_com_wind_max
(ParamFloat<px4::params::COM_WIND_MAX>) _param_com_wind_max,
(ParamFloat<px4::params::COM_SPOOLUP_TIME>) _param_com_spoolup_time
)
// optional parameters
+16
View File
@@ -1023,6 +1023,22 @@ PARAM_DEFINE_INT32(COM_ARM_ARSP_EN, 1);
*/
PARAM_DEFINE_INT32(COM_ARM_SDCARD, 1);
/**
* Enforced delay between arming and further navigation
*
* The minimal time from arming the motors until moving the vehicle is possible is COM_SPOOLUP_TIME seconds.
* Goal:
* - Motors and propellers spool up to idle speed before getting commanded to spin faster
* - Timeout for ESCs and smart batteries to successfulyy do failure checks
* e.g. for stuck rotors before the vehicle is off the ground
*
* @group Commander
* @min 0
* @max 5
* @unit s
*/
PARAM_DEFINE_FLOAT(COM_SPOOLUP_TIME, 1.0f);
/**
* Wind speed warning threshold
*
@@ -269,7 +269,7 @@ void FailureDetector::updateEscsStatus(const vehicle_status_s &vehicle_status, c
bool is_esc_failure = !is_all_escs_armed;
for (int i = 0; i < limited_esc_count; i++) {
is_esc_failure = is_esc_failure | (esc_status.esc[i].failures > 0);
is_esc_failure = is_esc_failure || (esc_status.esc[i].failures > 0);
}
_esc_failure_hysteresis.set_hysteresis_time_from(false, 300_ms);
@@ -131,15 +131,15 @@ private:
uORB::Publication<vehicle_thrust_setpoint_s> _vehicle_thrust_setpoint_pub{ORB_ID(vehicle_thrust_setpoint)};
uORB::Publication<vehicle_torque_setpoint_s> _vehicle_torque_setpoint_pub{ORB_ID(vehicle_torque_setpoint)};
actuator_controls_s _actuator_controls {}; /**< actuator control inputs */
manual_control_setpoint_s _manual_control_setpoint {}; /**< r/c channel data */
vehicle_attitude_setpoint_s _att_sp {}; /**< vehicle attitude setpoint */
vehicle_control_mode_s _vcontrol_mode {}; /**< vehicle control mode */
vehicle_local_position_s _local_pos {}; /**< local position */
vehicle_rates_setpoint_s _rates_sp {}; /* attitude rates setpoint */
vehicle_status_s _vehicle_status {}; /**< vehicle status */
actuator_controls_s _actuator_controls{};
manual_control_setpoint_s _manual_control_setpoint{};
vehicle_attitude_setpoint_s _att_sp{};
vehicle_control_mode_s _vcontrol_mode{};
vehicle_local_position_s _local_pos{};
vehicle_rates_setpoint_s _rates_sp{};
vehicle_status_s _vehicle_status{};
perf_counter_t _loop_perf; /**< loop performance counter */
perf_counter_t _loop_perf;
hrt_abstime _last_run{0};
@@ -185,12 +185,12 @@ private:
uORB::Publication<tecs_status_s> _tecs_status_pub{ORB_ID(tecs_status)};
uORB::PublicationMulti<orbit_status_s> _orbit_status_pub{ORB_ID(orbit_status)};
manual_control_setpoint_s _manual_control_setpoint {}; // r/c channel data
position_setpoint_triplet_s _pos_sp_triplet {}; // triplet of mission items
vehicle_attitude_setpoint_s _att_sp {}; // vehicle attitude setpoint
vehicle_control_mode_s _control_mode {};
vehicle_local_position_s _local_pos {}; // vehicle local position
vehicle_status_s _vehicle_status {}; // vehicle status
manual_control_setpoint_s _manual_control_setpoint{};
position_setpoint_triplet_s _pos_sp_triplet{};
vehicle_attitude_setpoint_s _att_sp{};
vehicle_control_mode_s _control_mode{};
vehicle_local_position_s _local_pos{};
vehicle_status_s _vehicle_status{};
double _current_latitude{0};
double _current_longitude{0};
@@ -212,8 +212,8 @@ private:
float _min_current_sp_distance_xy{FLT_MAX};
position_setpoint_s _hdg_hold_prev_wp {}; // position where heading hold started
position_setpoint_s _hdg_hold_curr_wp {}; // position to which heading hold flies
position_setpoint_s _hdg_hold_prev_wp{}; // position where heading hold started
position_setpoint_s _hdg_hold_curr_wp{}; // position to which heading hold flies
// [us] Last absolute time position control has been called
hrt_abstime _last_time_position_control_called{0};
@@ -234,7 +234,7 @@ void MulticopterPositionControl::parameters_update(bool force)
_param_mpc_tko_speed.set(math::min(_param_mpc_tko_speed.get(), _param_mpc_z_vel_max_up.get()));
_param_mpc_land_speed.set(math::min(_param_mpc_land_speed.get(), _param_mpc_z_vel_max_dn.get()));
_takeoff.setSpoolupTime(_param_mpc_spoolup_time.get());
_takeoff.setSpoolupTime(_param_com_spoolup_time.get());
_takeoff.setTakeoffRampTime(_param_mpc_tko_ramp_t.get());
_takeoff.generateInitialRampValue(_param_mpc_z_vel_p_acc.get());
}
@@ -147,7 +147,7 @@ private:
(ParamBool<px4::params::MPC_USE_HTE>) _param_mpc_use_hte,
// Takeoff / Land
(ParamFloat<px4::params::MPC_SPOOLUP_TIME>) _param_mpc_spoolup_time, /**< time to let motors spool up after arming */
(ParamFloat<px4::params::COM_SPOOLUP_TIME>) _param_com_spoolup_time, /**< time to let motors spool up after arming */
(ParamFloat<px4::params::MPC_TKO_RAMP_T>) _param_mpc_tko_ramp_t, /**< time constant for smooth takeoff ramp */
(ParamFloat<px4::params::MPC_TKO_SPEED>) _param_mpc_tko_speed,
(ParamFloat<px4::params::MPC_LAND_SPEED>) _param_mpc_land_speed,
@@ -94,7 +94,7 @@ public:
private:
TakeoffState _takeoff_state = TakeoffState::disarmed;
systemlib::Hysteresis _spoolup_time_hysteresis{false}; ///< becomes true MPC_SPOOLUP_TIME seconds after the vehicle was armed
systemlib::Hysteresis _spoolup_time_hysteresis{false}; ///< becomes true COM_SPOOLUP_TIME seconds after the vehicle was armed
float _takeoff_ramp_time{0.f};
float _takeoff_ramp_vz_init{0.f}; ///< verticval velocity resulting in zero thrust
@@ -780,22 +780,6 @@ PARAM_DEFINE_FLOAT(MPC_TKO_RAMP_T, 3.0f);
*/
PARAM_DEFINE_INT32(MPC_POS_MODE, 4);
/**
* Enforced delay between arming and takeoff
*
* For altitude controlled modes the time from arming the motors until
* a takeoff is possible gets forced to be at least MPC_SPOOLUP_TIME seconds
* to ensure the motors and propellers can sppol up and reach idle speed before
* getting commanded to spin faster. This delay is particularly useful for vehicles
* with slow motor spin-up e.g. because of large propellers.
*
* @min 0
* @max 10
* @unit s
* @group Multicopter Position Control
*/
PARAM_DEFINE_FLOAT(MPC_SPOOLUP_TIME, 1.0f);
/**
* Yaw mode.
*
@@ -117,13 +117,13 @@ private:
uORB::SubscriptionCallbackWorkItem _vehicle_attitude_sub{this, ORB_ID(vehicle_attitude)};
actuator_controls_s _actuators {}; /**< actuator control inputs */
manual_control_setpoint_s _manual_control_setpoint {}; /**< r/c channel data */
vehicle_attitude_setpoint_s _attitude_setpoint {}; /**< vehicle attitude setpoint */
vehicle_rates_setpoint_s _rates_setpoint {}; /**< vehicle bodyrates setpoint */
vehicle_control_mode_s _vcontrol_mode {}; /**< vehicle control mode */
actuator_controls_s _actuators{};
manual_control_setpoint_s _manual_control_setpoint{};
vehicle_attitude_setpoint_s _attitude_setpoint{};
vehicle_rates_setpoint_s _rates_setpoint{};
vehicle_control_mode_s _vcontrol_mode{};
perf_counter_t _loop_perf; /**< loop performance counter */
perf_counter_t _loop_perf;
DEFINE_PARAMETERS(
(ParamFloat<px4::params::UUV_ROLL_P>) _param_roll_p,
@@ -195,16 +195,6 @@ void UUVPOSControl::Run()
}
}
/* Manual Control mode (e.g. gamepad,...) - raw feedthrough no assistance */
if (_manual_control_setpoint_sub.update(&_manual_control_setpoint)) {
// This should be copied even if not in manual mode. Otherwise, the poll(...) call will keep
// returning immediately and this loop will eat up resources.
if (_vcontrol_mode.flag_control_manual_enabled && !_vcontrol_mode.flag_control_rates_enabled) {
/* manual/direct control */
}
}
/* Only publish if any of the proper modes are enabled */
if (_vcontrol_mode.flag_control_manual_enabled ||
_vcontrol_mode.flag_control_attitude_enabled) {
@@ -60,7 +60,6 @@
#include <uORB/Subscription.hpp>
#include <uORB/SubscriptionCallback.hpp>
#include <uORB/Publication.hpp>
#include <uORB/topics/manual_control_setpoint.h>
#include <uORB/topics/parameter_update.h>
#include <uORB/topics/trajectory_setpoint.h>
#include <uORB/topics/vehicle_attitude.h>
@@ -103,20 +102,17 @@ private:
uORB::SubscriptionInterval _parameter_update_sub{ORB_ID(parameter_update), 1_s};
uORB::Subscription _vehicle_attitude_sub{ORB_ID(vehicle_attitude)}; /**< current vehicle attitude */
uORB::Subscription _manual_control_setpoint_sub{ORB_ID(manual_control_setpoint)}; /**< notification of manual control updates */
uORB::Subscription _vehicle_attitude_sub{ORB_ID(vehicle_attitude)};
uORB::Subscription _trajectory_setpoint_sub{ORB_ID(trajectory_setpoint)};
uORB::Subscription _vcontrol_mode_sub{ORB_ID(vehicle_control_mode)}; /**< vehicle status subscription */
uORB::Subscription _vcontrol_mode_sub{ORB_ID(vehicle_control_mode)};
uORB::SubscriptionCallbackWorkItem _vehicle_local_position_sub{this, ORB_ID(vehicle_local_position)};
//actuator_controls_s _actuators {}; /**< actuator control inputs */
manual_control_setpoint_s _manual_control_setpoint {}; /**< r/c channel data */
vehicle_attitude_s _vehicle_attitude {}; /**< vehicle attitude */
trajectory_setpoint_s _trajectory_setpoint{}; /**< vehicle position setpoint */
vehicle_control_mode_s _vcontrol_mode {}; /**< vehicle control mode */
vehicle_attitude_s _vehicle_attitude{};
trajectory_setpoint_s _trajectory_setpoint{};
vehicle_control_mode_s _vcontrol_mode{};
perf_counter_t _loop_perf; /**< loop performance counter */
perf_counter_t _loop_perf;
DEFINE_PARAMETERS(
(ParamFloat<px4::params::UUV_GAIN_X_P>) _param_pose_gain_x,