aboutsummaryrefslogtreecommitdiff
path: root/src
diff options
context:
space:
mode:
authorLorenz Meier <lm@inf.ethz.ch>2014-05-07 14:29:30 +0200
committerLorenz Meier <lm@inf.ethz.ch>2014-05-07 14:29:30 +0200
commit973b193261fab69320f25fae68345a60d7678dc8 (patch)
tree0d171ae55ce2d76fb5af6551f28bead5f7604b9e /src
parentde5bdbb8638b1911e9956b49935071349f32ebb7 (diff)
downloadpx4-firmware-973b193261fab69320f25fae68345a60d7678dc8.tar.gz
px4-firmware-973b193261fab69320f25fae68345a60d7678dc8.tar.bz2
px4-firmware-973b193261fab69320f25fae68345a60d7678dc8.zip
Fixed comments and code style of UAVCAN node
Diffstat (limited to 'src')
-rw-r--r--src/modules/uavcan/uavcan_clock.cpp13
-rw-r--r--src/modules/uavcan/uavcan_main.cpp40
-rw-r--r--src/modules/uavcan/uavcan_main.hpp19
3 files changed, 55 insertions, 17 deletions
diff --git a/src/modules/uavcan/uavcan_clock.cpp b/src/modules/uavcan/uavcan_clock.cpp
index 0e844f346..e41d5f953 100644
--- a/src/modules/uavcan/uavcan_clock.cpp
+++ b/src/modules/uavcan/uavcan_clock.cpp
@@ -1,7 +1,6 @@
/****************************************************************************
*
- * Copyright (C) 2014 PX4 Development Team. All rights reserved.
- * Author: Pavel Kirienko <pavel.kirienko@gmail.com>
+ * Copyright (c) 2014 PX4 Development Team. All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
@@ -35,6 +34,14 @@
#include <uavcan_stm32/uavcan_stm32.hpp>
#include <drivers/drv_hrt.h>
+/**
+ * @file uavcan_clock.cpp
+ *
+ * Implements a clock for the CAN node.
+ *
+ * @author Pavel Kirienko <pavel.kirienko@gmail.com>
+ */
+
namespace uavcan_stm32
{
namespace clock
@@ -62,7 +69,7 @@ uavcan::uint64_t getUtcUSecFromCanInterrupt()
} // namespace clock
-SystemClock& SystemClock::instance()
+SystemClock &SystemClock::instance()
{
static SystemClock inst;
return inst;
diff --git a/src/modules/uavcan/uavcan_main.cpp b/src/modules/uavcan/uavcan_main.cpp
index bf6d4fb08..8d715e3b1 100644
--- a/src/modules/uavcan/uavcan_main.cpp
+++ b/src/modules/uavcan/uavcan_main.cpp
@@ -1,7 +1,6 @@
/****************************************************************************
*
- * Copyright (C) 2014 PX4 Development Team. All rights reserved.
- * Author: Pavel Kirienko <pavel.kirienko@gmail.com>
+ * Copyright (c) 2014 PX4 Development Team. All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
@@ -40,10 +39,18 @@
#include <arch/chip/chip.h>
#include "uavcan_main.hpp"
+/**
+ * @file uavcan_main.cpp
+ *
+ * Implements basic functinality of UAVCAN node.
+ *
+ * @author Pavel Kirienko <pavel.kirienko@gmail.com>
+ */
+
/*
* UavcanNode
*/
-UavcanNode* UavcanNode::_instance;
+UavcanNode *UavcanNode::_instance;
int UavcanNode::start(uavcan::NodeID node_id, uint32_t bitrate)
{
@@ -58,22 +65,25 @@ int UavcanNode::start(uavcan::NodeID node_id, uint32_t bitrate)
* If no transceiver is connected, the RX pin will float, occasionally causing CAN controller to
* fail during initialization.
*/
- stm32_configgpio (GPIO_CAN1_RX);
- stm32_configgpio (GPIO_CAN1_TX);
+ stm32_configgpio(GPIO_CAN1_RX);
+ stm32_configgpio(GPIO_CAN1_TX);
stm32_configgpio(GPIO_CAN2_RX | GPIO_PULLUP);
- stm32_configgpio (GPIO_CAN2_TX);
+ stm32_configgpio(GPIO_CAN2_TX);
/*
* CAN driver init
*/
static CanInitHelper can;
static bool can_initialized = false;
+
if (!can_initialized) {
const int can_init_res = can.init(bitrate);
+
if (can_init_res < 0) {
warnx("CAN driver init failed %i", can_init_res);
return can_init_res;
}
+
can_initialized = true;
}
@@ -81,11 +91,14 @@ int UavcanNode::start(uavcan::NodeID node_id, uint32_t bitrate)
* Node init
*/
_instance = new UavcanNode(can.driver, uavcan_stm32::SystemClock::instance());
+
if (_instance == nullptr) {
warnx("Out of memory");
return -1;
}
+
const int node_init_res = _instance->init(node_id);
+
if (node_init_res < 0) {
delete _instance;
_instance = nullptr;
@@ -96,9 +109,9 @@ int UavcanNode::start(uavcan::NodeID node_id, uint32_t bitrate)
/*
* Start the task. Normally it should never exit.
*/
- static auto run_trampoline = [](int, char*[]) {return UavcanNode::_instance->run();};
+ static auto run_trampoline = [](int, char *[]) {return UavcanNode::_instance->run();};
return task_spawn_cmd("uavcan", SCHED_DEFAULT, SCHED_PRIORITY_DEFAULT, StackSize,
- static_cast<main_t>(run_trampoline), nullptr);
+ static_cast<main_t>(run_trampoline), nullptr);
}
int UavcanNode::init(uavcan::NodeID node_id)
@@ -123,14 +136,17 @@ int UavcanNode::init(uavcan::NodeID node_id)
int UavcanNode::run()
{
_node.setStatusOk();
+
while (true) {
// TODO: ORB multiplexing
const int res = _node.spin(uavcan::MonotonicDuration::getInfinite());
+
if (res < 0) {
warnx("Spin error %i", res);
::sleep(1);
}
}
+
return -1;
}
@@ -158,32 +174,40 @@ int uavcan_main(int argc, char *argv[])
print_usage();
::exit(1);
}
+
/*
* Node ID
*/
const int node_id = atoi(argv[2]);
+
if (node_id < 0 || node_id > uavcan::NodeID::Max || !uavcan::NodeID(node_id).isUnicast()) {
warnx("Invalid Node ID %i", node_id);
::exit(1);
}
+
/*
* CAN bitrate
*/
long bitrate = 0;
+
if (argc > 3) {
bitrate = atol(argv[3]);
}
+
if (bitrate <= 0) {
bitrate = DEFAULT_CAN_BITRATE;
}
+
/*
* Start
*/
warnx("Node ID %i, bitrate %li", node_id, bitrate);
return UavcanNode::start(node_id, bitrate);
+
} else {
print_usage();
::exit(1);
}
+
return 0;
}
diff --git a/src/modules/uavcan/uavcan_main.hpp b/src/modules/uavcan/uavcan_main.hpp
index 8bd660cc5..b27449f1f 100644
--- a/src/modules/uavcan/uavcan_main.hpp
+++ b/src/modules/uavcan/uavcan_main.hpp
@@ -1,7 +1,6 @@
/****************************************************************************
*
- * Copyright (C) 2014 PX4 Development Team. All rights reserved.
- * Author: Pavel Kirienko <pavel.kirienko@gmail.com>
+ * Copyright (c) 2014 PX4 Development Team. All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
@@ -37,7 +36,15 @@
#include <uavcan_stm32/uavcan_stm32.hpp>
/**
- * Implements basic functinality of UAVCAN node.
+ * @file uavcan_main.hpp
+ *
+ * Defines basic functinality of UAVCAN node.
+ *
+ * @author Pavel Kirienko <pavel.kirienko@gmail.com>
+ */
+
+/**
+ * A UAVCAN node.
*/
class UavcanNode
{
@@ -49,18 +56,18 @@ public:
typedef uavcan::Node<MemPoolSize> Node;
typedef uavcan_stm32::CanInitHelper<RxQueueLenPerIface> CanInitHelper;
- UavcanNode(uavcan::ICanDriver& can_driver, uavcan::ISystemClock& system_clock)
+ UavcanNode(uavcan::ICanDriver &can_driver, uavcan::ISystemClock &system_clock)
: _node(can_driver, system_clock)
{ }
static int start(uavcan::NodeID node_id, uint32_t bitrate);
- Node& getNode() { return _node; }
+ Node &getNode() { return _node; }
private:
int init(uavcan::NodeID node_id);
int run();
- static UavcanNode* _instance;
+ static UavcanNode *_instance; ///< pointer to the library instance
Node _node;
};