aboutsummaryrefslogtreecommitdiff
path: root/src/modules/uavcan
diff options
context:
space:
mode:
authorLorenz Meier <lm@inf.ethz.ch>2014-11-13 10:31:16 +0100
committerLorenz Meier <lm@inf.ethz.ch>2014-11-13 10:31:16 +0100
commitd9989962a9ef06ce363082ed82c0ff2a647beabc (patch)
treec4f99bb3845118c07dfb705f0da95d5a850c097d /src/modules/uavcan
parentdf40637987e0434d7a03d9bc9e9803776cb81785 (diff)
parent7bc9a6257731a741ff309f060f6cf87c33c4a266 (diff)
downloadpx4-firmware-d9989962a9ef06ce363082ed82c0ff2a647beabc.tar.gz
px4-firmware-d9989962a9ef06ce363082ed82c0ff2a647beabc.tar.bz2
px4-firmware-d9989962a9ef06ce363082ed82c0ff2a647beabc.zip
Update motor test tool
Diffstat (limited to 'src/modules/uavcan')
-rw-r--r--src/modules/uavcan/actuators/esc.cpp27
-rw-r--r--src/modules/uavcan/actuators/esc.hpp8
-rw-r--r--src/modules/uavcan/uavcan_main.cpp29
-rw-r--r--src/modules/uavcan/uavcan_main.hpp5
4 files changed, 58 insertions, 11 deletions
diff --git a/src/modules/uavcan/actuators/esc.cpp b/src/modules/uavcan/actuators/esc.cpp
index 1990651ef..1d23099f3 100644
--- a/src/modules/uavcan/actuators/esc.cpp
+++ b/src/modules/uavcan/actuators/esc.cpp
@@ -40,6 +40,9 @@
#include "esc.hpp"
#include <systemlib/err.h>
+
+#define MOTOR_BIT(x) (1<<(x))
+
UavcanEscController::UavcanEscController(uavcan::INode &node) :
_node(node),
_uavcan_pub_raw_cmd(node),
@@ -95,9 +98,8 @@ void UavcanEscController::update_outputs(float *outputs, unsigned num_outputs)
static const int cmd_max = uavcan::equipment::esc::RawCommand::FieldTypes::cmd::RawValueType::max();
- if (_armed) {
- for (unsigned i = 0; i < num_outputs; i++) {
-
+ for (unsigned i = 0; i < num_outputs; i++) {
+ if (_armed_mask & MOTOR_BIT(i)) {
float scaled = (outputs[i] + 1.0F) * 0.5F * cmd_max;
if (scaled < 1.0F) {
scaled = 1.0F; // Since we're armed, we don't want to stop it completely
@@ -111,6 +113,8 @@ void UavcanEscController::update_outputs(float *outputs, unsigned num_outputs)
msg.cmd.push_back(static_cast<int>(scaled));
_esc_status.esc[i].esc_setpoint_raw = abs(static_cast<int>(scaled));
+ } else {
+ msg.cmd.push_back(static_cast<unsigned>(0));
}
}
@@ -121,9 +125,22 @@ void UavcanEscController::update_outputs(float *outputs, unsigned num_outputs)
(void)_uavcan_pub_raw_cmd.broadcast(msg);
}
-void UavcanEscController::arm_esc(bool arm)
+void UavcanEscController::arm_all_escs(bool arm)
+{
+ if (arm) {
+ _armed_mask = -1;
+ } else {
+ _armed_mask = 0;
+ }
+}
+
+void UavcanEscController::arm_single_esc(int num, bool arm)
{
- _armed = arm;
+ if (arm) {
+ _armed_mask = MOTOR_BIT(num);
+ } else {
+ _armed_mask = 0;
+ }
}
void UavcanEscController::esc_status_sub_cb(const uavcan::ReceivedDataStructure<uavcan::equipment::esc::Status> &msg)
diff --git a/src/modules/uavcan/actuators/esc.hpp b/src/modules/uavcan/actuators/esc.hpp
index f4a3877e6..12c035542 100644
--- a/src/modules/uavcan/actuators/esc.hpp
+++ b/src/modules/uavcan/actuators/esc.hpp
@@ -61,7 +61,8 @@ public:
void update_outputs(float *outputs, unsigned num_outputs);
- void arm_esc(bool arm);
+ void arm_all_escs(bool arm);
+ void arm_single_esc(int num, bool arm);
private:
/**
@@ -99,6 +100,11 @@ private:
uavcan::TimerEventForwarder<TimerCbBinder> _orb_timer;
/*
+ * ESC states
+ */
+ uint32_t _armed_mask = 0;
+
+ /*
* Perf counters
*/
perf_counter_t _perfcnt_invalid_input = perf_alloc(PC_COUNT, "uavcan_esc_invalid_input");
diff --git a/src/modules/uavcan/uavcan_main.cpp b/src/modules/uavcan/uavcan_main.cpp
index a8485ee44..2c543462e 100644
--- a/src/modules/uavcan/uavcan_main.cpp
+++ b/src/modules/uavcan/uavcan_main.cpp
@@ -279,6 +279,7 @@ int UavcanNode::run()
_output_count = 2;
_armed_sub = orb_subscribe(ORB_ID(actuator_armed));
+ _test_motor_sub = orb_subscribe(ORB_ID(test_motor));
actuator_outputs_s outputs;
memset(&outputs, 0, sizeof(outputs));
@@ -344,7 +345,13 @@ int UavcanNode::run()
}
// can we mix?
- if (controls_updated && (_mixers != nullptr)) {
+ if (_test_in_progress) {
+ float test_outputs[NUM_ACTUATOR_OUTPUTS] = {};
+ test_outputs[_test_motor.motor_number] = _test_motor.value*2.0f-1.0f;
+
+ // Output to the bus
+ _esc_controller.update_outputs(test_outputs, NUM_ACTUATOR_OUTPUTS);
+ } else if (controls_updated && (_mixers != nullptr)) {
// XXX one output group has 8 outputs max,
// but this driver could well serve multiple groups.
@@ -384,15 +391,27 @@ int UavcanNode::run()
}
}
- // Check arming state
+ // Check motor test state
bool updated = false;
+ orb_check(_test_motor_sub, &updated);
+
+ if (updated) {
+ orb_copy(ORB_ID(test_motor), _test_motor_sub, &_test_motor);
+
+ // Update the test status and check that we're not locked down
+ _test_in_progress = (_test_motor.value > 0);
+ _esc_controller.arm_single_esc(_test_motor.motor_number, _test_in_progress);
+ }
+
+ // Check arming state
orb_check(_armed_sub, &updated);
if (updated) {
orb_copy(ORB_ID(actuator_armed), _armed_sub, &_armed);
- // Update the armed status and check that we're not locked down
- bool set_armed = _armed.armed && !_armed.lockdown;
+ // Update the armed status and check that we're not locked down and motor
+ // test is not running
+ bool set_armed = _armed.armed && !_armed.lockdown && !_test_in_progress;
arm_actuators(set_armed);
}
@@ -429,7 +448,7 @@ int
UavcanNode::arm_actuators(bool arm)
{
_is_armed = arm;
- _esc_controller.arm_esc(arm);
+ _esc_controller.arm_all_escs(arm);
return OK;
}
diff --git a/src/modules/uavcan/uavcan_main.hpp b/src/modules/uavcan/uavcan_main.hpp
index be7db9741..274321f0d 100644
--- a/src/modules/uavcan/uavcan_main.hpp
+++ b/src/modules/uavcan/uavcan_main.hpp
@@ -41,6 +41,7 @@
#include <uORB/topics/actuator_controls.h>
#include <uORB/topics/actuator_outputs.h>
#include <uORB/topics/actuator_armed.h>
+#include <uORB/topics/test_motor.h>
#include "actuators/esc.hpp"
#include "sensors/sensor_bridge.hpp"
@@ -103,6 +104,10 @@ private:
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;
+ bool _test_in_progress = false;
+
unsigned _output_count = 0; ///< number of actuators currently available
static UavcanNode *_instance; ///< singleton pointer