AutoAPMS
Resilient Robot Mission Management
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
19namespace auto_apms_px4
20{
21
22std::string toStr(VehicleCommandClient::SendCommandResult result)
23{
24 switch (result) {
25 case VehicleCommandClient::SendCommandResult::ACCEPTED:
26 return "ACCEPTED";
27 case VehicleCommandClient::SendCommandResult::REJECTED:
28 return "REJECTED";
29 case VehicleCommandClient::SendCommandResult::TIMEOUT:
30 return "TIMEOUT";
31 default:
32 return "undefined";
33 }
34}
35
36VehicleCommandClient::VehicleCommandClient(rclcpp::Node & node, const std::chrono::milliseconds & command_timeout)
37: node_{node}, logger_{node.get_logger().get_child("vehicle_command_client")}, command_timeout_{command_timeout}
38{
39 // Create vehicle command publisher and acknowledgement signal subscriber
40 vehicle_command_pub_ = node_.create_publisher<px4_msgs::msg::VehicleCommand>("/fmu/in/vehicle_command", 10);
41
42 vehicle_command_ack_sub_ = node_.create_subscription<px4_msgs::msg::VehicleCommandAck>(
43 "/fmu/out/vehicle_command_ack", rclcpp::QoS(1).best_effort(),
44 [](px4_msgs::msg::VehicleCommandAck::UniquePtr msg) { (void)msg; });
45}
46
47VehicleCommandClient::SendCommandResult VehicleCommandClient::syncSendVehicleCommand(
48 uint32_t command, float param1, float param2, float param3, float param4, float param5, float param6,
49 float param7) const
50{
51 px4_msgs::msg::VehicleCommand cmd{};
52 cmd.command = command;
53 cmd.param1 = param1;
54 cmd.param2 = param2;
55 cmd.param3 = param3;
56 cmd.param4 = param4;
57 cmd.param5 = param5;
58 cmd.param6 = param6;
59 cmd.param7 = param7;
60 cmd.timestamp = node_.get_clock()->now().nanoseconds() / 1000;
61
62 return syncSendVehicleCommand(cmd);
63}
64
65VehicleCommandClient::SendCommandResult VehicleCommandClient::syncSendVehicleCommand(
66 const px4_msgs::msg::VehicleCommand & cmd) const
67{
68 SendCommandResult result = SendCommandResult::REJECTED;
69 rclcpp::WaitSet wait_set;
70 wait_set.add_subscription(vehicle_command_ack_sub_);
71
72 bool got_reply = false;
73 auto start_time = std::chrono::steady_clock::now();
74 vehicle_command_pub_->publish(cmd);
75
76 while (!got_reply) {
77 auto now = std::chrono::steady_clock::now();
78
79 if (now >= start_time + command_timeout_) {
80 break;
81 }
82
83 auto wait_ret = wait_set.wait(command_timeout_ - (now - start_time));
84
85 if (wait_ret.kind() == rclcpp::WaitResultKind::Ready) {
86 px4_msgs::msg::VehicleCommandAck ack;
87 rclcpp::MessageInfo info;
88
89 if (vehicle_command_ack_sub_->take(ack, info)) {
90 if (ack.command == cmd.command && ack.target_component == cmd.source_component) {
91 RCLCPP_DEBUG(logger_, "syncSendVehicleCommand: Command %i - received ack result %i", cmd.command, ack.result);
92 if (ack.result == px4_msgs::msg::VehicleCommandAck::VEHICLE_CMD_RESULT_ACCEPTED) {
93 result = SendCommandResult::ACCEPTED;
94 }
95 got_reply = true;
96 }
97 } else {
98 RCLCPP_DEBUG(logger_, "syncSendVehicleCommand: Command %i - message not valid", cmd.command);
99 }
100 }
101 }
102
103 wait_set.remove_subscription(vehicle_command_ack_sub_);
104
105 if (!got_reply) {
106 result = SendCommandResult::TIMEOUT;
107 RCLCPP_WARN(logger_, "syncSendVehicleCommand: Command %i - timeout, no ack received", cmd.command);
108 }
109
110 RCLCPP_DEBUG(logger_, "syncSendVehicleCommand: Command %i - returned %s", cmd.command, toStr(result).c_str());
111
112 return result;
113}
114
115bool VehicleCommandClient::arm() const
116{
117 return !syncSendVehicleCommand(VehicleCommand::VEHICLE_CMD_COMPONENT_ARM_DISARM, 1);
118}
119
120bool VehicleCommandClient::disarm() const
121{
122 return !syncSendVehicleCommand(VehicleCommand::VEHICLE_CMD_COMPONENT_ARM_DISARM, 0);
123}
124
126{
127 return !syncSendVehicleCommand(VehicleCommand::VEHICLE_CMD_MISSION_START, 0);
128}
129
130bool VehicleCommandClient::takeoff(float altitude_amsl_m, float heading_rad) const
131{
132 RCLCPP_DEBUG(logger_, "Takeoff parameters: altitude_amsl_m=%f heading_rad=%f", altitude_amsl_m, heading_rad);
133 return !syncSendVehicleCommand(
134 VehicleCommand::VEHICLE_CMD_NAV_TAKEOFF, NAN, NAN, NAN, heading_rad, NAN, NAN, altitude_amsl_m);
135}
136
137bool VehicleCommandClient::land() const { return !syncSendVehicleCommand(VehicleCommand::VEHICLE_CMD_NAV_LAND); }
138
139bool VehicleCommandClient::syncActivateFlightMode(uint8_t mode_id) const
140{
141 return !syncSendVehicleCommand(VehicleCommand::VEHICLE_CMD_SET_NAV_STATE, mode_id);
142}
143
144bool VehicleCommandClient::syncActivateFlightMode(const FlightMode & mode) const
145{
146 return syncActivateFlightMode(static_cast<uint8_t>(mode));
147}
148
149bool VehicleCommandClient::syncActivateFlightMode(const px4_ros2::ModeBase * const mode_ptr) const
150{
151 return syncActivateFlightMode(mode_ptr->id());
152}
153
154} // 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:26