Browse Source

CUAV CAN GPS support UAVCAN standard/indication/Button.uavcan

Co-authored-by: Daniel Agar <daniel@agar.ca>
release/1.12
Lorenz Meier 4 years ago committed by GitHub
parent
commit
2308cb8a40
No known key found for this signature in database
GPG Key ID: 4AEE18F83AFDEB23
  1. 9
      boards/cuav/can-gps-v1/init/rc.board_defaults
  2. 2
      boards/cuav/can-gps-v1/src/board_config.h
  3. 7
      src/drivers/uavcan/CMakeLists.txt
  4. 0
      src/drivers/uavcan/dsdl/standard/indication/21000.SafetyState.uavcan
  5. 11
      src/drivers/uavcan/dsdl/standard/indication/21001.Button.uavcan
  6. 2
      src/drivers/uavcan/safety_state.cpp
  7. 4
      src/drivers/uavcan/safety_state.hpp
  8. 7
      src/drivers/uavcannode/CMakeLists.txt
  9. 15
      src/drivers/uavcannode/UavcanNode.cpp
  10. 4
      src/drivers/uavcannode/UavcanNode.hpp

9
boards/cuav/can-gps-v1/init/rc.board_defaults

@ -2,14 +2,13 @@
# #
# board specific defaults # board specific defaults
#------------------------------------------------------------------------------ #------------------------------------------------------------------------------
neopixel start
tone_alarm start
if [ $AUTOCNF = yes ] if [ $AUTOCNF = yes ]
then then
# Disable safety switch by default
param set CBRK_IO_SAFETY 22027
fi fi
#safety_button start neopixel start
safety_button start
tone_alarm start

2
boards/cuav/can-gps-v1/src/board_config.h

@ -61,7 +61,7 @@
#define GPIO_CAN1_SILENT_S0 /* PB5 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTB|GPIO_PIN5) #define GPIO_CAN1_SILENT_S0 /* PB5 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTB|GPIO_PIN5)
#define GPIO_LED_SAFETY (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_SET|GPIO_PORTB|GPIO_PIN1) #define GPIO_LED_SAFETY (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_SET|GPIO_PORTB|GPIO_PIN1)
#define GPIO_BTN_SAFETY (GPIO_INPUT|GPIO_PULLUP|GPIO_PORTB|GPIO_PIN3) #define GPIO_BTN_SAFETY (GPIO_INPUT|GPIO_PULLDOWN|GPIO_PORTB|GPIO_PIN3)
/* Tone alarm output. */ /* Tone alarm output. */
#define TONE_ALARM_TIMER 2 /* timer 2 */ #define TONE_ALARM_TIMER 2 /* timer 2 */

7
src/drivers/uavcan/CMakeLists.txt

@ -94,7 +94,12 @@ target_include_directories(uavcan_${UAVCAN_DRIVER}_driver PUBLIC
# generated DSDL # generated DSDL
set(DSDLC_INPUTS "${CMAKE_CURRENT_SOURCE_DIR}/dsdl/com" "${CMAKE_CURRENT_SOURCE_DIR}/dsdl/ardupilot" "${LIBUAVCAN_DIR}/dsdl/uavcan") set(DSDLC_DIR "${CMAKE_CURRENT_SOURCE_DIR}/dsdl")
set(DSDLC_INPUTS
"${DSDLC_DIR}/com"
"${DSDLC_DIR}/standard"
"${LIBUAVCAN_DIR}/dsdl/uavcan"
)
set(DSDLC_OUTPUT "${CMAKE_CURRENT_BINARY_DIR}/include/dsdlc_generated") set(DSDLC_OUTPUT "${CMAKE_CURRENT_BINARY_DIR}/include/dsdlc_generated")
set(DSDLC_INPUT_FILES) set(DSDLC_INPUT_FILES)

0
src/drivers/uavcan/dsdl/ardupilot/indication/20000.SafetyState.uavcan → src/drivers/uavcan/dsdl/standard/indication/21000.SafetyState.uavcan

11
src/drivers/uavcan/dsdl/standard/indication/21001.Button.uavcan

@ -0,0 +1,11 @@
#
# support for buttons on UAVCAN
# while a button is being pressed this message should be sent at 10Hz
uint8 BUTTON_SAFETY = 1
uint8 button
# number of 0.1s units the button has been pressed for. If over 255
# then send 255
uint8 press_time

2
src/drivers/uavcan/safety_state.cpp

@ -63,7 +63,7 @@ void UavcanSafetyState::periodic_update(const uavcan::TimerEvent &)
actuator_armed_s actuator_armed; actuator_armed_s actuator_armed;
if (_actuator_armed_sub.update(&actuator_armed)) { if (_actuator_armed_sub.update(&actuator_armed)) {
ardupilot::indication::SafetyState cmd; standard::indication::SafetyState cmd;
if (actuator_armed.armed || actuator_armed.prearmed) { if (actuator_armed.armed || actuator_armed.prearmed) {
cmd.status = cmd.STATUS_SAFETY_OFF; cmd.status = cmd.STATUS_SAFETY_OFF;

4
src/drivers/uavcan/safety_state.hpp

@ -42,7 +42,7 @@
#pragma once #pragma once
#include <uavcan/uavcan.hpp> #include <uavcan/uavcan.hpp>
#include <ardupilot/indication/SafetyState.hpp> #include <standard/indication/SafetyState.hpp>
#include <uORB/Subscription.hpp> #include <uORB/Subscription.hpp>
#include <uORB/topics/actuator_armed.h> #include <uORB/topics/actuator_armed.h>
@ -74,7 +74,7 @@ private:
/* /*
* Publish CAN Safety state led * Publish CAN Safety state led
*/ */
uavcan::Publisher<ardupilot::indication::SafetyState> _safety_state_pub; uavcan::Publisher<standard::indication::SafetyState> _safety_state_pub;
uavcan::TimerEventForwarder<TimerCbBinder> _timer; uavcan::TimerEventForwarder<TimerCbBinder> _timer;

7
src/drivers/uavcannode/CMakeLists.txt

@ -94,7 +94,12 @@ target_include_directories(uavcan_${UAVCAN_DRIVER}_driver PUBLIC
# generated DSDL # generated DSDL
set(DSDLC_INPUTS "${PX4_SOURCE_DIR}/src/drivers/uavcan/dsdl/com" "${LIBUAVCAN_DIR}/dsdl/uavcan") set(DSDLC_DIR "${PX4_SOURCE_DIR}/src/drivers/uavcan/dsdl")
set(DSDLC_INPUTS
"${DSDLC_DIR}/com"
"${DSDLC_DIR}/standard"
"${LIBUAVCAN_DIR}/dsdl/uavcan"
)
set(DSDLC_OUTPUT "${CMAKE_CURRENT_BINARY_DIR}/include/dsdlc_generated") set(DSDLC_OUTPUT "${CMAKE_CURRENT_BINARY_DIR}/include/dsdlc_generated")
set(DSDLC_INPUT_FILES) set(DSDLC_INPUT_FILES)

15
src/drivers/uavcannode/UavcanNode.cpp

@ -83,6 +83,7 @@ UavcanNode::UavcanNode(uavcan::ICanDriver &can_driver, uavcan::ISystemClock &sys
_raw_air_data_publisher(_node), _raw_air_data_publisher(_node),
_range_sensor_measurement(_node), _range_sensor_measurement(_node),
_flow_measurement_publisher(_node), _flow_measurement_publisher(_node),
_indication_button_publisher(_node),
_param_server(_node), _param_server(_node),
_cycle_perf(perf_alloc(PC_ELAPSED, MODULE_NAME": cycle time")), _cycle_perf(perf_alloc(PC_ELAPSED, MODULE_NAME": cycle time")),
_interval_perf(perf_alloc(PC_INTERVAL, MODULE_NAME": cycle interval")), _interval_perf(perf_alloc(PC_INTERVAL, MODULE_NAME": cycle interval")),
@ -521,6 +522,20 @@ void UavcanNode::Run()
} }
} }
// safety -> standard::indication::button
if (_safety_sub.updated()) {
safety_s safety;
if (_safety_sub.copy(&safety)) {
if (safety.safety_switch_available) {
standard::indication::Button Button{};
Button.button = standard::indication::Button::BUTTON_SAFETY;
Button.press_time = safety.safety_off ? UINT8_MAX : 0;
_indication_button_publisher.broadcast(Button);
}
}
}
perf_end(_cycle_perf); perf_end(_cycle_perf);
pthread_mutex_unlock(&_node_mutex); pthread_mutex_unlock(&_node_mutex);

4
src/drivers/uavcannode/UavcanNode.hpp

@ -66,6 +66,7 @@
#include <uavcan/equipment/power/BatteryInfo.hpp> #include <uavcan/equipment/power/BatteryInfo.hpp>
#include <uavcan/equipment/range_sensor/Measurement.hpp> #include <uavcan/equipment/range_sensor/Measurement.hpp>
#include <standard/indication/Button.hpp>
#include <com/hex/equipment/flow/Measurement.hpp> #include <com/hex/equipment/flow/Measurement.hpp>
#include <lib/parameters/param.h> #include <lib/parameters/param.h>
@ -78,6 +79,7 @@
#include <uORB/topics/differential_pressure.h> #include <uORB/topics/differential_pressure.h>
#include <uORB/topics/distance_sensor.h> #include <uORB/topics/distance_sensor.h>
#include <uORB/topics/optical_flow.h> #include <uORB/topics/optical_flow.h>
#include <uORB/topics/safety.h>
#include <uORB/topics/sensor_baro.h> #include <uORB/topics/sensor_baro.h>
#include <uORB/topics/sensor_mag.h> #include <uORB/topics/sensor_mag.h>
#include <uORB/topics/sensor_gps.h> #include <uORB/topics/sensor_gps.h>
@ -182,6 +184,7 @@ private:
uavcan::Publisher<uavcan::equipment::air_data::RawAirData> _raw_air_data_publisher; uavcan::Publisher<uavcan::equipment::air_data::RawAirData> _raw_air_data_publisher;
uavcan::Publisher<uavcan::equipment::range_sensor::Measurement> _range_sensor_measurement; uavcan::Publisher<uavcan::equipment::range_sensor::Measurement> _range_sensor_measurement;
uavcan::Publisher<com::hex::equipment::flow::Measurement> _flow_measurement_publisher; uavcan::Publisher<com::hex::equipment::flow::Measurement> _flow_measurement_publisher;
uavcan::Publisher<standard::indication::Button> _indication_button_publisher;
hrt_abstime _last_static_temperature_publish{0}; hrt_abstime _last_static_temperature_publish{0};
@ -197,6 +200,7 @@ private:
{this, ORB_ID(distance_sensor), 3}, {this, ORB_ID(distance_sensor), 3},
}; };
uORB::SubscriptionCallbackWorkItem _optical_flow_sub{this, ORB_ID(optical_flow)}; uORB::SubscriptionCallbackWorkItem _optical_flow_sub{this, ORB_ID(optical_flow)};
uORB::SubscriptionCallbackWorkItem _safety_sub{this, ORB_ID(safety)};
uORB::SubscriptionCallbackWorkItem _sensor_baro_sub{this, ORB_ID(sensor_baro)}; uORB::SubscriptionCallbackWorkItem _sensor_baro_sub{this, ORB_ID(sensor_baro)};
uORB::SubscriptionCallbackWorkItem _sensor_mag_sub{this, ORB_ID(sensor_mag)}; uORB::SubscriptionCallbackWorkItem _sensor_mag_sub{this, ORB_ID(sensor_mag)};
uORB::SubscriptionCallbackWorkItem _sensor_gps_sub{this, ORB_ID(sensor_gps)}; uORB::SubscriptionCallbackWorkItem _sensor_gps_sub{this, ORB_ID(sensor_gps)};

Loading…
Cancel
Save