Browse Source

Fixed formating and cleanup

sbg
blah 9 years ago committed by Lorenz Meier
parent
commit
1188aa138c
  1. 11
      src/modules/uavcan/actuators/hardpoint.cpp
  2. 21
      src/modules/uavcan/actuators/hardpoint.hpp
  3. 33
      src/modules/uavcan/uavcan_main.cpp
  4. 18
      src/modules/uavcan/uavcan_main.hpp

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

@ -56,6 +56,9 @@ UavcanHardpointController::~UavcanHardpointController()
int UavcanHardpointController::init() int UavcanHardpointController::init()
{ {
/*
* 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)); _timer.startPeriodic(uavcan::MonotonicDuration::fromMSec(1000 / MAX_RATE_HZ));
return 0; return 0;
@ -67,6 +70,7 @@ void UavcanHardpointController::set_command(uint8_t hardpoint_id, uint16_t comma
_cmd.command = command; _cmd.command = command;
_cmd.hardpoint_id = hardpoint_id; _cmd.hardpoint_id = hardpoint_id;
_cmd_set = true; _cmd_set = true;
/* /*
* Rate limiting - we don't want to congest the bus * Rate limiting - we don't want to congest the bus
*/ */
@ -86,13 +90,14 @@ void UavcanHardpointController::set_command(uint8_t hardpoint_id, uint16_t comma
/* /*
* Start the periodic update timer after a command is set * Start the periodic update timer after a command is set
*/ */
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 UavcanHardpointController::periodic_update(const uavcan::TimerEvent &) void UavcanHardpointController::periodic_update(const uavcan::TimerEvent &)
{ {
/*
* Broadcast command at MAX_RATE_HZ
*/
(void)_uavcan_pub_raw_cmd.broadcast(_cmd); (void)_uavcan_pub_raw_cmd.broadcast(_cmd);
//do something
} }

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

@ -34,7 +34,6 @@
/** /**
* @file hardpoint.hpp * @file hardpoint.hpp
* *
*
* @author Andreas Jochum <Andreas@NicaDrone.com> * @author Andreas Jochum <Andreas@NicaDrone.com>
*/ */
@ -44,8 +43,10 @@
#include <uavcan/equipment/hardpoint/Command.hpp> #include <uavcan/equipment/hardpoint/Command.hpp>
#include <uavcan/equipment/hardpoint/Status.hpp> #include <uavcan/equipment/hardpoint/Status.hpp>
#include <systemlib/perf_counter.h> #include <systemlib/perf_counter.h>
//#include <uORB/topics/esc_status.h>
/**
* @brief The UavcanHardpointController class
*/
class UavcanHardpointController class UavcanHardpointController
{ {
@ -53,15 +54,23 @@ public:
UavcanHardpointController(uavcan::INode &node); UavcanHardpointController(uavcan::INode &node);
~UavcanHardpointController(); ~UavcanHardpointController();
/*
* setup periodic updater
*/
int init(); int init();
/*
* set command
*/
void set_command(uint8_t hardpoint_id, uint16_t command); void set_command(uint8_t hardpoint_id, uint16_t command);
private: private:
/*
* Max update rate to avoid exessive bus traffic
*/
static constexpr unsigned MAX_RATE_HZ = 1; ///< XXX make this configurable static constexpr unsigned MAX_RATE_HZ = 1; ///< XXX make this configurable
uavcan::equipment::hardpoint::Command _cmd; uavcan::equipment::hardpoint::Command _cmd;
bool _cmd_set = false; bool _cmd_set = false;
@ -71,16 +80,12 @@ private:
typedef uavcan::MethodBinder<UavcanHardpointController *, void (UavcanHardpointController::*)(const uavcan::TimerEvent &)> typedef uavcan::MethodBinder<UavcanHardpointController *, void (UavcanHardpointController::*)(const uavcan::TimerEvent &)>
TimerCbBinder; TimerCbBinder;
// hardpoint_status_s _hardpoint_status = {};
orb_advert_t _hardpoint_status_pub = nullptr;
/* /*
* libuavcan related things * libuavcan related things
*/ */
uavcan::MonotonicTime _prev_cmd_pub; ///< rate limiting uavcan::MonotonicTime _prev_cmd_pub; ///< rate limiting
uavcan::INode &_node; uavcan::INode &_node;
uavcan::Publisher<uavcan::equipment::hardpoint::Command> _uavcan_pub_raw_cmd; uavcan::Publisher<uavcan::equipment::hardpoint::Command> _uavcan_pub_raw_cmd;
// uavcan::Subscriber<uavcan::equipment::hardpoint::Status, StatusCbBinder> _uavcan_sub_status;
uavcan::TimerEventForwarder<TimerCbBinder> _timer; uavcan::TimerEventForwarder<TimerCbBinder> _timer;
}; };

33
src/modules/uavcan/uavcan_main.cpp

@ -31,6 +31,16 @@
* *
****************************************************************************/ ****************************************************************************/
/**
* @file uavcan_main.cpp
*
* Implements basic functionality of UAVCAN node.
*
* @author Pavel Kirienko <pavel.kirienko@gmail.com>
* David Sidrane <david_s5@nscdg.com>
* Andreas Jochum <Andreas@NicaDrone.com>
*/
#include <px4_config.h> #include <px4_config.h>
#include <cstdlib> #include <cstdlib>
@ -62,16 +72,6 @@
// #include <sys/types.h> and leaving OK undefined // #include <sys/types.h> and leaving OK undefined
# define OK 0 # define OK 0
/**
* @file uavcan_main.cpp
*
* Implements basic functionality of UAVCAN node.
*
* @author Pavel Kirienko <pavel.kirienko@gmail.com>
* David Sidrane <david_s5@nscdg.com>
*/
/* /*
* UavcanNode * UavcanNode
*/ */
@ -1222,7 +1222,8 @@ void UavcanNode::shrink()
(void)pthread_mutex_unlock(&_node_mutex); (void)pthread_mutex_unlock(&_node_mutex);
} }
void UavcanNode::hardpoint_controller_set(uint8_t hardpoint_id, uint16_t command){ void UavcanNode::hardpoint_controller_set(uint8_t hardpoint_id, uint16_t command)
{
_hardpoint_controller.set_command(hardpoint_id, command); _hardpoint_controller.set_command(hardpoint_id, command);
} }
/* /*
@ -1375,6 +1376,7 @@ int uavcan_main(int argc, char *argv[])
return inst->set_param(nodeid, argv[4], argv[5]); return inst->set_param(nodeid, argv[4], argv[5]);
} }
} }
if (!std::strcmp(argv[1], "hardpoint")) { if (!std::strcmp(argv[1], "hardpoint")) {
if (!std::strcmp(argv[2], "set") && argc > 4) { if (!std::strcmp(argv[2], "set") && argc > 4) {
const int hardpoint_id = atoi(argv[3]); const int hardpoint_id = atoi(argv[3]);
@ -1386,15 +1388,16 @@ int uavcan_main(int argc, char *argv[])
command >= 0 && command >= 0 &&
command < 65536) { command < 65536) {
inst->hardpoint_controller_set((uint8_t) hardpoint_id, (uint16_t) command); inst->hardpoint_controller_set((uint8_t) hardpoint_id, (uint16_t) command);
}
else { } else {
errx(1, "Are you nuts?"); errx(1, "Are you nuts?");
} }
}
else { } else {
errx(1, "Are you nuts?"); errx(1, "Are you nuts?");
} }
} }
if (!std::strcmp(argv[1], "stop")) { if (!std::strcmp(argv[1], "stop")) {
if (fw) { if (fw) {

18
src/modules/uavcan/uavcan_main.hpp

@ -31,6 +31,15 @@
* *
****************************************************************************/ ****************************************************************************/
/**
* @file uavcan_main.hpp
*
* Defines basic functinality of UAVCAN node.
*
* @author Pavel Kirienko <pavel.kirienko@gmail.com>
* Andreas Jochum <Andreas@NicaDrone.com>
*/
#pragma once #pragma once
#include <px4_config.h> #include <px4_config.h>
@ -59,14 +68,6 @@
#include "uavcan_servers.hpp" #include "uavcan_servers.hpp"
#include "allocator.hpp" #include "allocator.hpp"
/**
* @file uavcan_main.hpp
*
* Defines basic functinality of UAVCAN node.
*
* @author Pavel Kirienko <pavel.kirienko@gmail.com>
*/
#define NUM_ACTUATOR_CONTROL_GROUPS_UAVCAN 4 #define NUM_ACTUATOR_CONTROL_GROUPS_UAVCAN 4
// we add two to allow for actuator_direct and busevent // we add two to allow for actuator_direct and busevent
@ -124,6 +125,7 @@ public:
void subscribe(); void subscribe();
int teardown(); int teardown();
int arm_actuators(bool arm); int arm_actuators(bool arm);
void print_info(); void print_info();

Loading…
Cancel
Save