Skip to content

Commit bf08213

Browse files
committed
update uavcan hardpoint: add ability to use it via mavlink cmd and during mission and removed send_command() dedicated for usage via mavlink console
1 parent 92b1f51 commit bf08213

File tree

2 files changed

+34
-31
lines changed

2 files changed

+34
-31
lines changed

src/drivers/uavcan/actuators/hardpoint.cpp

Lines changed: 26 additions & 22 deletions
Original file line numberDiff line numberDiff line change
@@ -38,14 +38,13 @@
3838
*/
3939

4040
#include "hardpoint.hpp"
41-
#include <systemlib/err.h>
4241

4342
UavcanHardpointController::UavcanHardpointController(uavcan::INode &node) :
4443
_node(node),
45-
_uavcan_pub_raw_cmd(node),
44+
_uavcan_pub_hardpoint(node),
4645
_timer(node)
4746
{
48-
_uavcan_pub_raw_cmd.setPriority(uavcan::TransferPriority::MiddleLower);
47+
_uavcan_pub_hardpoint.setPriority(uavcan::TransferPriority::MiddleLower);
4948
}
5049

5150
UavcanHardpointController::~UavcanHardpointController()
@@ -59,33 +58,38 @@ UavcanHardpointController::init()
5958
/*
6059
* Setup timer and call back function for periodic updates
6160
*/
62-
_timer.setCallback(TimerCbBinder(this, &UavcanHardpointController::periodic_update));
61+
if (!_timer.isRunning()) {
62+
_timer.setCallback(TimerCbBinder(this, &UavcanHardpointController::periodic_update));
63+
_timer.startPeriodic(uavcan::MonotonicDuration::fromMSec(1000 / MAX_UPDATE_RATE_HZ));
64+
}
65+
6366
return 0;
6467
}
6568

6669
void
67-
UavcanHardpointController::set_command(uint8_t hardpoint_id, uint16_t command)
70+
UavcanHardpointController::periodic_update(const uavcan::TimerEvent &)
6871
{
69-
_cmd.command = command;
70-
_cmd.hardpoint_id = hardpoint_id;
72+
if (_vehicle_command_sub.updated()) {
73+
vehicle_command_s vehicle_command;
7174

72-
/*
73-
* Publish the command message to the bus
74-
*/
75-
_uavcan_pub_raw_cmd.broadcast(_cmd);
75+
if (_vehicle_command_sub.copy(&vehicle_command)) {
76+
if (vehicle_command.command == vehicle_command_s::VEHICLE_CMD_DO_GRIPPER) {
77+
_cmd.hardpoint_id = vehicle_command.param1;
78+
_cmd.command = vehicle_command.param2;
79+
_next_publish_time = 0;
80+
}
81+
}
82+
}
7683

7784
/*
78-
* Start the periodic update timer after a command is set
85+
* According to the MAV_CMD_DO_GRIPPER cmd, Instance (hardpoint_id) should be at least 1
7986
*/
80-
if (!_timer.isRunning()) {
81-
_timer.startPeriodic(uavcan::MonotonicDuration::fromMSec(1000 / MAX_RATE_HZ));
82-
}
83-
84-
}
87+
if (_cmd.hardpoint_id >= 1) {
88+
const hrt_abstime timestamp_now = hrt_absolute_time();
8589

86-
void
87-
UavcanHardpointController::periodic_update(const uavcan::TimerEvent &)
88-
{
89-
// Broadcast command at MAX_RATE_HZ
90-
_uavcan_pub_raw_cmd.broadcast(_cmd);
90+
if (timestamp_now > _next_publish_time) {
91+
_next_publish_time = timestamp_now + 1000000 / PUBLISH_RATE_HZ;
92+
_uavcan_pub_hardpoint.broadcast(_cmd);
93+
}
94+
}
9195
}

src/drivers/uavcan/actuators/hardpoint.hpp

Lines changed: 8 additions & 9 deletions
Original file line numberDiff line numberDiff line change
@@ -42,7 +42,8 @@
4242
#include <uavcan/uavcan.hpp>
4343
#include <uavcan/equipment/hardpoint/Command.hpp>
4444
#include <uavcan/equipment/hardpoint/Status.hpp>
45-
#include <perf/perf_counter.h>
45+
#include <uORB/Subscription.hpp>
46+
#include <uORB/topics/vehicle_command.h>
4647

4748
/**
4849
* @brief The UavcanHardpointController class
@@ -59,17 +60,12 @@ class UavcanHardpointController
5960
*/
6061
int init();
6162

62-
63-
/*
64-
* set command
65-
*/
66-
void set_command(uint8_t hardpoint_id, uint16_t command);
67-
6863
private:
6964
/*
7065
* Max update rate to avoid exessive bus traffic
7166
*/
72-
static constexpr unsigned MAX_RATE_HZ = 1; ///< XXX make this configurable
67+
static constexpr unsigned MAX_UPDATE_RATE_HZ = 10;
68+
static constexpr unsigned PUBLISH_RATE_HZ = 1;
7369

7470
uavcan::equipment::hardpoint::Command _cmd;
7571

@@ -83,7 +79,10 @@ class UavcanHardpointController
8379
* libuavcan related things
8480
*/
8581
uavcan::INode &_node;
86-
uavcan::Publisher<uavcan::equipment::hardpoint::Command> _uavcan_pub_raw_cmd;
82+
uavcan::Publisher<uavcan::equipment::hardpoint::Command> _uavcan_pub_hardpoint;
8783
uavcan::TimerEventForwarder<TimerCbBinder> _timer;
8884

85+
uORB::Subscription _vehicle_command_sub{ORB_ID(vehicle_command)};
86+
87+
hrt_abstime _next_publish_time = 0;
8988
};

0 commit comments

Comments
 (0)