aboutsummaryrefslogtreecommitdiff
path: root/src/modules/uavcan/uavcan_main.hpp
diff options
context:
space:
mode:
authorThomas Gubler <thomasgubler@gmail.com>2015-01-28 16:29:14 +0100
committerThomas Gubler <thomasgubler@gmail.com>2015-01-28 16:29:14 +0100
commit2728889f7886e3ab2fea16941d29e60ece0d4449 (patch)
treeca9994d71205731ee4bb404175c2cf8f13fcc539 /src/modules/uavcan/uavcan_main.hpp
parentf23e603d02ba416ae250770cdaad6a859d6bae69 (diff)
parent1dcc5c49cc75778bcdde770f2d6c2700dd2bec2e (diff)
downloadpx4-firmware-2728889f7886e3ab2fea16941d29e60ece0d4449.tar.gz
px4-firmware-2728889f7886e3ab2fea16941d29e60ece0d4449.tar.bz2
px4-firmware-2728889f7886e3ab2fea16941d29e60ece0d4449.zip
Merge remote-tracking branch 'upstream/master' into ros_messagelayer_merge_attctlposctl
Diffstat (limited to 'src/modules/uavcan/uavcan_main.hpp')
-rw-r--r--src/modules/uavcan/uavcan_main.hpp18
1 files changed, 11 insertions, 7 deletions
diff --git a/src/modules/uavcan/uavcan_main.hpp b/src/modules/uavcan/uavcan_main.hpp
index 98f2e5ad4..19b9b4b48 100644
--- a/src/modules/uavcan/uavcan_main.hpp
+++ b/src/modules/uavcan/uavcan_main.hpp
@@ -34,9 +34,9 @@
#pragma once
#include <nuttx/config.h>
-
#include <uavcan_stm32/uavcan_stm32.hpp>
#include <drivers/device/device.h>
+#include <systemlib/perf_counter.h>
#include <uORB/topics/actuator_controls.h>
#include <uORB/topics/actuator_outputs.h>
@@ -66,7 +66,7 @@
*/
class UavcanNode : public device::CDev
{
- static constexpr unsigned MemPoolSize = 10752;
+ static constexpr unsigned MemPoolSize = 10752; ///< Refer to the libuavcan manual to learn why
static constexpr unsigned RxQueueLenPerIface = 64;
static constexpr unsigned StackSize = 3000;
@@ -107,11 +107,11 @@ private:
int _task = -1; ///< handle to the OS task
bool _task_should_exit = false; ///< flag to indicate to tear down the CAN driver
int _armed_sub = -1; ///< uORB subscription of the arming status
- actuator_armed_s _armed; ///< the arming request of the system
+ actuator_armed_s _armed = {}; ///< the arming request of the system
bool _is_armed = false; ///< the arming status of the actuators on the bus
int _test_motor_sub = -1; ///< uORB subscription of the test_motor status
- test_motor_s _test_motor;
+ test_motor_s _test_motor = {};
bool _test_in_progress = false;
unsigned _output_count = 0; ///< number of actuators currently available
@@ -135,11 +135,15 @@ private:
unsigned _poll_fds_num = 0;
int _actuator_direct_sub = -1; ///< uORB subscription of the actuator_direct topic
- uint8_t _actuator_direct_poll_fd_num;
- actuator_direct_s _actuator_direct;
+ uint8_t _actuator_direct_poll_fd_num = 0;
+ actuator_direct_s _actuator_direct = {};
- actuator_outputs_s _outputs;
+ actuator_outputs_s _outputs = {};
// index into _poll_fds for each _control_subs handle
uint8_t _poll_ids[NUM_ACTUATOR_CONTROL_GROUPS_UAVCAN];
+
+ perf_counter_t _perfcnt_node_spin_elapsed = perf_alloc(PC_ELAPSED, "uavcan_node_spin_elapsed");
+ perf_counter_t _perfcnt_esc_mixer_output_elapsed = perf_alloc(PC_ELAPSED, "uavcan_esc_mixer_output_elapsed");
+ perf_counter_t _perfcnt_esc_mixer_total_elapsed = perf_alloc(PC_ELAPSED, "uavcan_esc_mixer_total_elapsed");
};