38
38
*/
39
39
40
40
#include " hardpoint.hpp"
41
- #include < systemlib/err.h>
42
41
43
42
UavcanHardpointController::UavcanHardpointController (uavcan::INode &node) :
44
43
_node(node),
45
- _uavcan_pub_raw_cmd (node),
44
+ _uavcan_pub_hardpoint (node),
46
45
_timer(node)
47
46
{
48
- _uavcan_pub_raw_cmd .setPriority (uavcan::TransferPriority::MiddleLower);
47
+ _uavcan_pub_hardpoint .setPriority (uavcan::TransferPriority::MiddleLower);
49
48
}
50
49
51
50
UavcanHardpointController::~UavcanHardpointController ()
@@ -59,33 +58,38 @@ UavcanHardpointController::init()
59
58
/*
60
59
* Setup timer and call back function for periodic updates
61
60
*/
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
+
63
66
return 0 ;
64
67
}
65
68
66
69
void
67
- UavcanHardpointController::set_command ( uint8_t hardpoint_id, uint16_t command )
70
+ UavcanHardpointController::periodic_update ( const uavcan::TimerEvent & )
68
71
{
69
- _cmd. command = command;
70
- _cmd. hardpoint_id = hardpoint_id ;
72
+ if (_vehicle_command_sub. updated ()) {
73
+ vehicle_command_s vehicle_command ;
71
74
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
+ }
76
83
77
84
/*
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
79
86
*/
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 ();
85
89
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
+ }
91
95
}
0 commit comments