PX4 Firmware
PX4 Autopilot Software http://px4.io
UavcanEscController Class Reference

#include <esc.hpp>

Collaboration diagram for UavcanEscController:

Public Member Functions

 UavcanEscController (uavcan::INode &node)
 
 ~UavcanEscController ()
 
int init ()
 
void update_outputs (bool stop_motors, uint16_t outputs[MAX_ACTUATORS], unsigned num_outputs)
 
void set_rotor_count (uint8_t count)
 Sets the number of rotors. More...
 

Static Public Member Functions

static int max_output_value ()
 

Static Public Attributes

static constexpr int MAX_ACTUATORS = MixingOutput::MAX_ACTUATORS
 
static constexpr unsigned MAX_RATE_HZ = 200
 XXX make this configurable. More...
 
static constexpr uint16_t DISARMED_OUTPUT_VALUE = UINT16_MAX
 

Private Types

typedef uavcan::MethodBinder< UavcanEscController *, void(UavcanEscController::*)(const uavcan::ReceivedDataStructure< uavcan::equipment::esc::Status > &)> StatusCbBinder
 
typedef uavcan::MethodBinder< UavcanEscController *, void(UavcanEscController::*)(const uavcan::TimerEvent &)> TimerCbBinder
 

Private Member Functions

void esc_status_sub_cb (const uavcan::ReceivedDataStructure< uavcan::equipment::esc::Status > &msg)
 ESC status message reception will be reported via this callback. More...
 
void orb_pub_timer_cb (const uavcan::TimerEvent &event)
 ESC status will be published to ORB from this callback (fixed rate). More...
 
uint8_t check_escs_status ()
 Checks all the ESCs freshness based on timestamp, if an ESC exceeds the timeout then is flagged offline. More...
 

Private Attributes

esc_status_s _esc_status {}
 
uORB::PublicationMulti< esc_status_s_esc_status_pub {ORB_ID(esc_status)}
 
uint8_t _rotor_count {0}
 
uavcan::MonotonicTime _prev_cmd_pub
 rate limiting More...
 
uavcan::INode & _node
 
uavcan::Publisher< uavcan::equipment::esc::RawCommand > _uavcan_pub_raw_cmd
 
uavcan::Subscriber< uavcan::equipment::esc::Status, StatusCbBinder_uavcan_sub_status
 
uavcan::TimerEventForwarder< TimerCbBinder_orb_timer
 
uint8_t _max_number_of_nonzero_outputs {0}
 

Static Private Attributes

static constexpr unsigned ESC_STATUS_UPDATE_RATE_HZ = 10
 
static constexpr unsigned UAVCAN_COMMAND_TRANSFER_PRIORITY = 5
 0..31, inclusive, 0 - highest, 31 - lowest More...
 

Detailed Description

Definition at line 57 of file esc.hpp.

Member Typedef Documentation

◆ StatusCbBinder

typedef uavcan::MethodBinder<UavcanEscController *, void (UavcanEscController::*)(const uavcan::ReceivedDataStructure<uavcan::equipment::esc::Status>&)> UavcanEscController::StatusCbBinder
private

Definition at line 98 of file esc.hpp.

◆ TimerCbBinder

typedef uavcan::MethodBinder<UavcanEscController *, void (UavcanEscController::*)(const uavcan::TimerEvent &)> UavcanEscController::TimerCbBinder
private

Definition at line 101 of file esc.hpp.

Constructor & Destructor Documentation

◆ UavcanEscController()

UavcanEscController::UavcanEscController ( uavcan::INode &  node)

Definition at line 48 of file esc.cpp.

References _uavcan_pub_raw_cmd, and UAVCAN_COMMAND_TRANSFER_PRIORITY.

◆ ~UavcanEscController()

UavcanEscController::~UavcanEscController ( )

Definition at line 57 of file esc.cpp.

Member Function Documentation

◆ check_escs_status()

uint8_t UavcanEscController::check_escs_status ( )
private

Checks all the ESCs freshness based on timestamp, if an ESC exceeds the timeout then is flagged offline.

Definition at line 171 of file esc.cpp.

References _esc_status, esc_status_s::esc, hrt_absolute_time(), hrt_abstime, and esc_report_s::timestamp.

Referenced by max_output_value(), and orb_pub_timer_cb().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ esc_status_sub_cb()

void UavcanEscController::esc_status_sub_cb ( const uavcan::ReceivedDataStructure< uavcan::equipment::esc::Status > &  msg)
private

ESC status message reception will be reported via this callback.

Definition at line 143 of file esc.cpp.

References _esc_status, esc_status_s::esc, esc_report_s::esc_address, and hrt_absolute_time().

Referenced by init(), and max_output_value().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ init()

int UavcanEscController::init ( )

Definition at line 62 of file esc.cpp.

References _orb_timer, _uavcan_sub_status, esc_status_sub_cb(), ESC_STATUS_UPDATE_RATE_HZ, and orb_pub_timer_cb().

Referenced by UavcanNode::init().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ max_output_value()

static int UavcanEscController::max_output_value ( )
inlinestatic

Definition at line 76 of file esc.hpp.

References check_escs_status(), esc_status_sub_cb(), math::max(), msg, and orb_pub_timer_cb().

Referenced by UavcanNode::init().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ orb_pub_timer_cb()

void UavcanEscController::orb_pub_timer_cb ( const uavcan::TimerEvent &  event)
private

ESC status will be published to ORB from this callback (fixed rate).

Definition at line 159 of file esc.cpp.

References _esc_status, _esc_status_pub, _rotor_count, check_escs_status(), esc_status_s::counter, esc_status_s::esc_connectiontype, esc_status_s::esc_count, esc_status_s::esc_online_flags, hrt_absolute_time(), uORB::PublicationMulti< T >::publish(), and esc_status_s::timestamp.

Referenced by init(), and max_output_value().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ set_rotor_count()

void UavcanEscController::set_rotor_count ( uint8_t  count)
inline

Sets the number of rotors.

Definition at line 74 of file esc.hpp.

References _rotor_count.

Referenced by UavcanMixingInterface::mixerChanged().

Here is the caller graph for this function:

◆ update_outputs()

void UavcanEscController::update_outputs ( bool  stop_motors,
uint16_t  outputs[MAX_ACTUATORS],
unsigned  num_outputs 
)

Definition at line 80 of file esc.cpp.

References _max_number_of_nonzero_outputs, _node, _prev_cmd_pub, _uavcan_pub_raw_cmd, DISARMED_OUTPUT_VALUE, MAX_RATE_HZ, and msg.

Referenced by UavcanMixingInterface::updateOutputs().

Here is the caller graph for this function:

Member Data Documentation

◆ _esc_status

esc_status_s UavcanEscController::_esc_status {}
private

Definition at line 103 of file esc.hpp.

Referenced by check_escs_status(), esc_status_sub_cb(), and orb_pub_timer_cb().

◆ _esc_status_pub

uORB::PublicationMulti<esc_status_s> UavcanEscController::_esc_status_pub {ORB_ID(esc_status)}
private

Definition at line 105 of file esc.hpp.

Referenced by orb_pub_timer_cb().

◆ _max_number_of_nonzero_outputs

uint8_t UavcanEscController::_max_number_of_nonzero_outputs {0}
private

Definition at line 121 of file esc.hpp.

Referenced by update_outputs().

◆ _node

uavcan::INode& UavcanEscController::_node
private

Definition at line 113 of file esc.hpp.

Referenced by update_outputs().

◆ _orb_timer

uavcan::TimerEventForwarder<TimerCbBinder> UavcanEscController::_orb_timer
private

Definition at line 116 of file esc.hpp.

Referenced by init().

◆ _prev_cmd_pub

uavcan::MonotonicTime UavcanEscController::_prev_cmd_pub
private

rate limiting

Definition at line 112 of file esc.hpp.

Referenced by update_outputs().

◆ _rotor_count

uint8_t UavcanEscController::_rotor_count {0}
private

Definition at line 107 of file esc.hpp.

Referenced by orb_pub_timer_cb(), and set_rotor_count().

◆ _uavcan_pub_raw_cmd

uavcan::Publisher<uavcan::equipment::esc::RawCommand> UavcanEscController::_uavcan_pub_raw_cmd
private

Definition at line 114 of file esc.hpp.

Referenced by UavcanEscController(), and update_outputs().

◆ _uavcan_sub_status

uavcan::Subscriber<uavcan::equipment::esc::Status, StatusCbBinder> UavcanEscController::_uavcan_sub_status
private

Definition at line 115 of file esc.hpp.

Referenced by init().

◆ DISARMED_OUTPUT_VALUE

constexpr uint16_t UavcanEscController::DISARMED_OUTPUT_VALUE = UINT16_MAX
static

Definition at line 62 of file esc.hpp.

Referenced by UavcanNode::init(), and update_outputs().

◆ ESC_STATUS_UPDATE_RATE_HZ

constexpr unsigned UavcanEscController::ESC_STATUS_UPDATE_RATE_HZ = 10
staticprivate

Definition at line 94 of file esc.hpp.

Referenced by init().

◆ MAX_ACTUATORS

constexpr int UavcanEscController::MAX_ACTUATORS = MixingOutput::MAX_ACTUATORS
static

Definition at line 60 of file esc.hpp.

◆ MAX_RATE_HZ

constexpr unsigned UavcanEscController::MAX_RATE_HZ = 200
static

XXX make this configurable.

Definition at line 61 of file esc.hpp.

Referenced by UavcanNode::init(), and update_outputs().

◆ UAVCAN_COMMAND_TRANSFER_PRIORITY

constexpr unsigned UavcanEscController::UAVCAN_COMMAND_TRANSFER_PRIORITY = 5
staticprivate

0..31, inclusive, 0 - highest, 31 - lowest

Definition at line 95 of file esc.hpp.

Referenced by UavcanEscController().


The documentation for this class was generated from the following files: