Browse Source

clean up....

sbg
blah 9 years ago committed by Lorenz Meier
parent
commit
39fc9c7761
  1. 15
      src/modules/uavcan/actuators/hardpoint.cpp
  2. 3
      src/modules/uavcan/actuators/hardpoint.hpp

15
src/modules/uavcan/actuators/hardpoint.cpp

@ -60,27 +60,15 @@ int UavcanHardpointController::init()
* Setup timer and call back function for periodic updates * Setup timer and call back function for periodic updates
*/ */
_timer.setCallback(TimerCbBinder(this, &UavcanHardpointController::periodic_update)); _timer.setCallback(TimerCbBinder(this, &UavcanHardpointController::periodic_update));
_timer.startPeriodic(uavcan::MonotonicDuration::fromMSec(1000 / MAX_RATE_HZ));
return 0; return 0;
} }
void UavcanHardpointController::set_command(uint8_t hardpoint_id, uint16_t command) void UavcanHardpointController::set_command(uint8_t hardpoint_id, uint16_t command)
{ {
(void)pthread_mutex_lock(&_node_mutex);
_cmd.command = command; _cmd.command = command;
_cmd.hardpoint_id = hardpoint_id; _cmd.hardpoint_id = hardpoint_id;
_cmd_set = true;
/*
* Rate limiting - we don't want to congest the bus
*/
const auto timestamp = _node.getMonotonicTime();
if ((timestamp - _prev_cmd_pub).toUSec() < (1000000 / MAX_RATE_HZ)) {
return;
}
_prev_cmd_pub = timestamp;
/* /*
* Publish the command message to the bus * Publish the command message to the bus
@ -93,6 +81,7 @@ void UavcanHardpointController::set_command(uint8_t hardpoint_id, uint16_t comma
if (!_timer.isRunning()) { if (!_timer.isRunning()) {
_timer.startPeriodic(uavcan::MonotonicDuration::fromMSec(1000 / MAX_RATE_HZ)); _timer.startPeriodic(uavcan::MonotonicDuration::fromMSec(1000 / MAX_RATE_HZ));
} }
(void)pthread_mutex_lock(&_node_mutex);
} }
void UavcanHardpointController::periodic_update(const uavcan::TimerEvent &) void UavcanHardpointController::periodic_update(const uavcan::TimerEvent &)
{ {

3
src/modules/uavcan/actuators/hardpoint.hpp

@ -73,13 +73,12 @@ private:
uavcan::equipment::hardpoint::Command _cmd; uavcan::equipment::hardpoint::Command _cmd;
bool _cmd_set = false;
void periodic_update(const uavcan::TimerEvent &); void periodic_update(const uavcan::TimerEvent &);
typedef uavcan::MethodBinder<UavcanHardpointController *, void (UavcanHardpointController::*)(const uavcan::TimerEvent &)> typedef uavcan::MethodBinder<UavcanHardpointController *, void (UavcanHardpointController::*)(const uavcan::TimerEvent &)>
TimerCbBinder; TimerCbBinder;
pthread_mutex_t _node_mutex;
/* /*
* libuavcan related things * libuavcan related things
*/ */

Loading…
Cancel
Save