AutoAPMS
Streamlining behaviors in ROS 2
Loading...
Searching...
No Matches
vehicle_command_client.cpp
1// Copyright 2024 Robin Müller
2//
3// Licensed under the Apache License, Version 2.0 (the "License");
4// you may not use this file except in compliance with the License.
5// You may obtain a copy of the License at
6//
7// https://www.apache.org/licenses/LICENSE-2.0
8//
9// Unless required by applicable law or agreed to in writing, software
10// distributed under the License is distributed on an "AS IS" BASIS,
11// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
12// See the License for the specific language governing permissions and
13// limitations under the License.
14
15#include "auto_apms_px4/vehicle_command_client.hpp"
16
17#include <functional>
18
19#include "px4_ros2/utils/message_version.hpp"
20
21namespace auto_apms_px4
22{
23
24std::string toStr(VehicleCommandClient::SendCommandResult result)
25{
26 switch (result) {
27 case VehicleCommandClient::SendCommandResult::ACCEPTED:
28 return "ACCEPTED";
29 case VehicleCommandClient::SendCommandResult::REJECTED:
30 return "REJECTED";
31 case VehicleCommandClient::SendCommandResult::TIMEOUT:
32 return "TIMEOUT";
33 default:
34 return "undefined";
35 }
36}
37
38VehicleCommandClient::VehicleCommandClient(rclcpp::Node & node, const std::chrono::milliseconds & command_timeout)
39: node_{node}, logger_{node.get_logger().get_child("vehicle_command_client")}, command_timeout_{command_timeout}
40{
41 // Create vehicle command publisher and acknowledgement signal subscriber
42 vehicle_command_pub_ = node_.create_publisher<px4_msgs::msg::VehicleCommand>(
43 "/fmu/in/vehicle_command" + px4_ros2::getMessageNameVersion<px4_msgs::msg::VehicleCommand>(), 10);
44
45 vehicle_command_ack_sub_ = node_.create_subscription<px4_msgs::msg::VehicleCommandAck>(
46 "/fmu/out/vehicle_command_ack" + px4_ros2::getMessageNameVersion<px4_msgs::msg::VehicleCommandAck>(),
47 rclcpp::QoS(1).best_effort(), [](px4_msgs::msg::VehicleCommandAck::UniquePtr msg) { (void)msg; });
48}
49
50VehicleCommandClient::SendCommandResult VehicleCommandClient::syncSendVehicleCommand(
51 uint32_t command, float param1, float param2, float param3, float param4, float param5, float param6,
52 float param7) const
53{
54 px4_msgs::msg::VehicleCommand cmd{};
55 cmd.command = command;
56 cmd.param1 = param1;
57 cmd.param2 = param2;
58 cmd.param3 = param3;
59 cmd.param4 = param4;
60 cmd.param5 = param5;
61 cmd.param6 = param6;
62 cmd.param7 = param7;
63 cmd.timestamp = node_.get_clock()->now().nanoseconds() / 1000;
64
65 return syncSendVehicleCommand(cmd);
66}
67
68VehicleCommandClient::SendCommandResult VehicleCommandClient::syncSendVehicleCommand(
69 const px4_msgs::msg::VehicleCommand & cmd) const
70{
71 SendCommandResult result = SendCommandResult::REJECTED;
72 using AckWaitSet = rclcpp::StaticWaitSet<1, 0, 0, 0, 0, 0>;
73 AckWaitSet wait_set({{{vehicle_command_ack_sub_}}});
74
75 bool got_reply = false;
76 auto start_time = std::chrono::steady_clock::now();
77 vehicle_command_pub_->publish(cmd);
78
79 while (!got_reply) {
80 auto now = std::chrono::steady_clock::now();
81
82 if (now >= start_time + command_timeout_) {
83 break;
84 }
85
86 rclcpp::WaitResult<AckWaitSet> wait_ret = wait_set.wait(command_timeout_ - (now - start_time));
87
88 if (wait_ret.kind() == rclcpp::WaitResultKind::Ready) {
89 px4_msgs::msg::VehicleCommandAck ack;
90 rclcpp::MessageInfo info;
91
92 if (vehicle_command_ack_sub_->take(ack, info)) {
93 if (ack.command == cmd.command && ack.target_component == cmd.source_component) {
94 RCLCPP_DEBUG(
95 logger_, "syncSendVehicleCommand: Command %i - Received acknowledgement %i", cmd.command, ack.result);
96 if (ack.result == px4_msgs::msg::VehicleCommandAck::VEHICLE_CMD_RESULT_ACCEPTED) {
97 result = SendCommandResult::ACCEPTED;
98 }
99 got_reply = true;
100 }
101 } else {
102 RCLCPP_DEBUG(logger_, "syncSendVehicleCommand: Command %i - Acknowledgement message not valid", cmd.command);
103 }
104 }
105 }
106
107 if (!got_reply) {
108 result = SendCommandResult::TIMEOUT;
109 RCLCPP_WARN(logger_, "syncSendVehicleCommand: Command %i - Timeout, no acknowledgement received", cmd.command);
110 }
111
112 RCLCPP_DEBUG(logger_, "syncSendVehicleCommand: Command %i - Result code: %s", cmd.command, toStr(result).c_str());
113
114 return result;
115}
116
117bool VehicleCommandClient::arm() const
118{
119 return !syncSendVehicleCommand(VehicleCommand::VEHICLE_CMD_COMPONENT_ARM_DISARM, 1);
120}
121
122bool VehicleCommandClient::disarm() const
123{
124 return !syncSendVehicleCommand(VehicleCommand::VEHICLE_CMD_COMPONENT_ARM_DISARM, 0);
125}
126
128{
129 return !syncSendVehicleCommand(VehicleCommand::VEHICLE_CMD_MISSION_START, 0);
130}
131
132bool VehicleCommandClient::takeoff(float altitude_amsl_m, float heading_rad) const
133{
134 RCLCPP_DEBUG(logger_, "Takeoff parameters: altitude_amsl_m=%f heading_rad=%f", altitude_amsl_m, heading_rad);
135 return !syncSendVehicleCommand(
136 VehicleCommand::VEHICLE_CMD_NAV_TAKEOFF, NAN, NAN, NAN, heading_rad, NAN, NAN, altitude_amsl_m);
137}
138
139bool VehicleCommandClient::land() const { return !syncSendVehicleCommand(VehicleCommand::VEHICLE_CMD_NAV_LAND); }
140
141bool VehicleCommandClient::syncActivateFlightMode(uint8_t mode_id) const
142{
143 return !syncSendVehicleCommand(VehicleCommand::VEHICLE_CMD_SET_NAV_STATE, mode_id);
144}
145
146bool VehicleCommandClient::syncActivateFlightMode(const FlightMode & mode) const
147{
148 return syncActivateFlightMode(static_cast<uint8_t>(mode));
149}
150
151bool VehicleCommandClient::syncActivateFlightMode(const px4_ros2::ModeBase * const mode_ptr) const
152{
153 return syncActivateFlightMode(mode_ptr->id());
154}
155
156} // namespace auto_apms_px4
bool startMission() const
(Re)starts the uploaded mission plan.
const char * toStr(const ActionNodeErrorCode &err)
Convert the action error code to string.
Implementation of PX4 mode peers offered by px4_ros2_cpp enabling integration with AutoAPMS.
Definition mode.hpp:28