Modulo 5.0.0
Loading...
Searching...
No Matches
RobotControllerInterface.cpp
1#include "modulo_controllers/RobotControllerInterface.hpp"
2
3#include "ament_index_cpp/get_package_share_directory.hpp"
4#include <hardware_interface/types/hardware_interface_type_values.hpp>
5
6#include <state_representation/exceptions/JointNotFoundException.hpp>
7
8using namespace state_representation;
9
10namespace modulo_controllers {
11
12static const std::map<std::string, JointStateVariable> interface_map =// NOLINT(cert-err58-cpp)
13 {{hardware_interface::HW_IF_POSITION, JointStateVariable::POSITIONS},
14 {hardware_interface::HW_IF_VELOCITY, JointStateVariable::VELOCITIES},
15 {hardware_interface::HW_IF_ACCELERATION, JointStateVariable::ACCELERATIONS},
16 {hardware_interface::HW_IF_EFFORT, JointStateVariable::TORQUES}};
17
19
21 bool robot_model_required, const std::string& control_type, bool load_geometries)
22 : ControllerInterface(true),
23 control_type_(control_type),
24 robot_model_required_(robot_model_required),
25 load_geometries_(load_geometries),
26 new_joint_command_ready_(false),
27 command_decay_factor_(0.0),
28 command_rate_limit_(std::numeric_limits<double>::infinity()) {
29 if (!control_type.empty() && interface_map.find(control_type) == interface_map.cend()) {
30 RCLCPP_ERROR(get_node()->get_logger(), "Invalid control type: %s", control_type.c_str());
31 throw std::invalid_argument("Invalid control type");
32 }
33}
34
35rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn RobotControllerInterface::add_interfaces() {
37 std::make_shared<Parameter<std::string>>("task_space_frame"),
38 "The frame name in the robot model to use for kinematics calculations (defaults to the last frame in the "
39 "model)");
41 "sort_joints", true,
42 "If true, re-arrange the 'joints' parameter into a physically correct order according to the robot model");
44 std::make_shared<Parameter<std::string>>("ft_sensor_name"),
45 "Optionally, the name of a force-torque sensor in the hardware interface");
47 std::make_shared<Parameter<std::string>>("ft_sensor_reference_frame"),
48 "The reference frame of the force-torque sensor in the robot model");
50 "command_half_life", 0.1,
51 "A time constant for the exponential decay of the commanded velocity, acceleration or torque if no new command "
52 "is set");
54 "command_rate_limit", command_rate_limit_,
55 "The maximum allowable change in command on any interface expressed in command units / second");
56 return CallbackReturn::SUCCESS;
57}
58
59rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn RobotControllerInterface::on_configure() {
60 if (*get_parameter("robot_description")) {
61 std::stringstream timestamp;
62 timestamp << std::time(nullptr);
63 auto urdf_path = "/tmp/" + hardware_name_ + "_" + timestamp.str();
64 try {
65 robot_model::Model::create_urdf_from_string(get_parameter_value<std::string>("robot_description"), urdf_path);
66 if (load_geometries_) {
67 robot_ = std::make_shared<robot_model::Model>(hardware_name_, urdf_path, [](const std::string& package_name) {
68 return ament_index_cpp::get_package_share_directory(package_name) + "/";
69 });
70 RCLCPP_DEBUG(get_node()->get_logger(), "Generated robot model with collision features");
71 } else {
72 robot_ = std::make_shared<robot_model::Model>(hardware_name_, urdf_path);
73 RCLCPP_DEBUG(get_node()->get_logger(), "Generated robot model");
74 }
75 } catch (const std::exception& ex) {
78 "Could not generate robot model with temporary urdf from string content at path %s: %s", urdf_path.c_str(),
79 ex.what());
80 }
81 }
82 if (robot_model_required_ && robot_ == nullptr) {
83 RCLCPP_ERROR(get_node()->get_logger(), "Robot model is not available even though it's required by the controller.");
84 return CallbackReturn::ERROR;
85 }
86
87 if (robot_) {
88 if (get_parameter("task_space_frame")->is_empty()) {
89 task_space_frame_ = robot_->get_frames().back();
90 } else {
92 if (!robot_->get_pinocchio_model().existFrame(task_space_frame_)) {
94 get_node()->get_logger(), "Provided task space frame %s does not exist in the robot model!",
95 task_space_frame_.c_str());
96 return CallbackReturn::ERROR;
97 }
98 }
99 }
100
101 auto joints = get_parameter("joints");
102 if (joints->is_empty() && !control_type_.empty()) {
104 get_node()->get_logger(), "The 'joints' parameter is required for a non-zero control type %s!",
105 control_type_.c_str());
106 return CallbackReturn::ERROR;
107 }
108 joints_ = joints->get_parameter_value<std::vector<std::string>>();
109
110 // sort the interface joint names using the robot model if necessary
111 if (get_parameter_value<bool>("sort_joints") && robot_) {
112 if (joints_.size() != robot_->get_number_of_joints()) {
114 get_node()->get_logger(),
115 "The number of interface joints (%zu) does not match the number of joints in the robot model (%u)",
116 joints_.size(), robot_->get_number_of_joints());
117 }
118 std::vector<std::string> ordered_joints;
119 for (const auto& ordered_name : robot_->get_joint_frames()) {
120 for (const auto& joint_name : joints_) {
121 if (joint_name == ordered_name) {
122 ordered_joints.push_back(joint_name);
123 break;
124 }
125 }
126 }
127 if (ordered_joints.size() < joints_.size()) {
129 get_node()->get_logger(), "%zu interface joints were not found in the robot model",
130 joints_.size() - ordered_joints.size());
131 return CallbackReturn::ERROR;
132 }
133 joints_ = ordered_joints;
134 }
135 joint_state_ = JointState(hardware_name_, joints_);
136
137 // set command interfaces from joints
138 if (!control_type_.empty()) {
139 if (control_type_ == hardware_interface::HW_IF_POSITION) {
140 previous_joint_command_values_ = std::vector<double>(joints_.size(), std::numeric_limits<double>::quiet_NaN());
141 } else {
142 previous_joint_command_values_ = std::vector<double>(joints_.size(), 0.0);
143 }
144 for (const auto& joint : joints_) {
145 add_command_interface(joint, control_type_);
146 }
147 }
148
149 auto ft_sensor_name = get_parameter("ft_sensor_name");
150 if (!ft_sensor_name->is_empty()) {
151 ft_sensor_name_ = ft_sensor_name->get_parameter_value<std::string>();
152 auto ft_sensor_reference_frame = get_parameter("ft_sensor_reference_frame");
153 if (ft_sensor_reference_frame->is_empty()) {
155 get_node()->get_logger(),
156 "The 'ft_sensor_reference_frame' parameter cannot be empty if a force-torque sensor is specified!");
157 return CallbackReturn::ERROR;
158 }
159 ft_sensor_reference_frame_ = ft_sensor_reference_frame->get_parameter_value<std::string>();
160 // TODO check that there is no joint in between
161 if (robot_ != nullptr && !robot_->get_pinocchio_model().existFrame(ft_sensor_reference_frame_)) {
163 get_node()->get_logger(), "The FT sensor reference frame '%s' does not exist on the robot model!",
165 return CallbackReturn::ERROR;
166 }
167 }
168
169 command_decay_factor_ = -log(0.5) / get_parameter_value<double>("command_half_life");
170 command_rate_limit_ = get_parameter_value<double>("command_rate_limit");
171
172 RCLCPP_DEBUG(get_node()->get_logger(), "Configuration of RobotControllerInterface successful");
173 return CallbackReturn::SUCCESS;
174}
175
176rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn RobotControllerInterface::on_activate() {
177 // initialize a force torque sensor state if applicable
178 if (!ft_sensor_name_.empty()) {
179 try {
186 } catch (const std::out_of_range&) {
188 get_node()->get_logger(), "The force torque sensor '%s' does not have all the expected state interfaces!",
189 ft_sensor_name_.c_str());
190 return CallbackReturn::FAILURE;
191 }
193 }
194
195 RCLCPP_DEBUG(get_node()->get_logger(), "Activation of RobotControllerInterface successful");
196 return CallbackReturn::SUCCESS;
197}
198
199controller_interface::return_type RobotControllerInterface::read_state_interfaces() {
201 if (status != controller_interface::return_type::OK) {
202 return status;
203 }
204
205 if (joint_state_.get_size() > 0 && joint_state_.is_empty()) {
206 RCLCPP_DEBUG(get_node()->get_logger(), "Reading first joint state");
207 joint_state_.set_zero();
208 }
209
210 for (const auto& joint : joints_) {
212 unsigned int joint_index;
213 try {
214 joint_index = joint_state_.get_joint_index(joint);
215 } catch (exceptions::JointNotFoundException& ex) {
217 return controller_interface::return_type::ERROR;
218 }
219 for (const auto& [interface, value] : data) {
220 if (!std::isfinite(value)) {
222 get_node()->get_logger(), *get_node()->get_clock(), 1000, "Value of state interface '%s/%s' is not finite",
223 joint.c_str(), interface.c_str());
224 return controller_interface::return_type::ERROR;
225 }
226 switch (interface_map.at(interface)) {
227 case JointStateVariable::POSITIONS:
228 joint_state_.set_position(value, joint_index);
229 break;
230 case JointStateVariable::VELOCITIES:
231 joint_state_.set_velocity(value, joint_index);
232 break;
233 case JointStateVariable::ACCELERATIONS:
234 joint_state_.set_acceleration(value, joint_index);
235 break;
236 case JointStateVariable::TORQUES:
237 joint_state_.set_torque(value, joint_index);
238 break;
239 default:
240 break;
241 }
242 }
243 }
244
245 if (!ft_sensor_name_.empty()) {
247 std::vector<double> wrench = {ft_sensor.at("force.x"), ft_sensor.at("force.y"), ft_sensor.at("force.z"),
248 ft_sensor.at("torque.x"), ft_sensor.at("torque.y"), ft_sensor.at("torque.z")};
249 ft_sensor_.set_wrench(wrench);
250 }
251
252 return controller_interface::return_type::OK;
253}
254
255controller_interface::return_type RobotControllerInterface::write_command_interfaces(const rclcpp::Duration& period) {
256 if (!control_type_.empty()) {
257 double decay = 1.0 - command_decay_factor_ * period.seconds();
258 decay = std::max(0.0, decay);
259 double rate_limit = command_rate_limit_ * period.seconds();
260
261 auto joint_command_values = joint_command_values_.readFromRT();
262 if (joint_command_values == nullptr) {
263 new_joint_command_ready_ = false;
264 }
265
266 for (std::size_t index = 0; index < joints_.size(); ++index) {
267 double previous_command = previous_joint_command_values_.at(index);
268 if (new_joint_command_ready_) {
269 auto new_command = joint_command_values->at(index);
270 if (std::isfinite(previous_command) && std::abs(new_command - previous_command) > rate_limit) {
273 }
274 set_command_interface(joints_.at(index), control_type_, new_command);
275 previous_joint_command_values_.at(index) = new_command;
276 } else if (control_type_ != hardware_interface::HW_IF_POSITION) {
278 set_command_interface(joints_.at(index), control_type_, new_command);
279 previous_joint_command_values_.at(index) = new_command;
280 }
281 }
282 new_joint_command_ready_ = false;
283 }
284
286}
287
289 return joint_state_;
290}
291
293 // TODO check if recompute is necessary?
295 return cartesian_state_;
296}
297
299 return ft_sensor_;
300}
301
303 if (robot_ != nullptr) {
304 cartesian_state_ = robot_->forward_kinematics(joint_state_, task_space_frame_);
305 cartesian_state_.set_twist(robot_->forward_velocity(joint_state_, task_space_frame_).get_twist());
306
307 if (!ft_sensor_.is_empty() && (ft_sensor_.get_reference_frame() == cartesian_state_.get_name())) {
308 auto ft_sensor_in_robot_frame = cartesian_state_ * ft_sensor_;
309 cartesian_state_.set_wrench(ft_sensor_in_robot_frame.get_wrench());
310 }
311 }
312}
313
314void RobotControllerInterface::set_joint_command(const JointState& joint_command) {
315 if (!joint_command) {
316 RCLCPP_DEBUG(get_node()->get_logger(), "set_joint_command called with an empty JointState");
317 return;
318 }
319
320 std::vector<double> joint_command_values;
321 joint_command_values.reserve(joints_.size());
322
323 for (const auto& joint : joints_) {
324 try {
325 switch (interface_map.at(control_type_)) {
326 case JointStateVariable::POSITIONS:
327 joint_command_values.push_back(joint_command.get_position(joint));
328 break;
329 case JointStateVariable::VELOCITIES:
330 joint_command_values.push_back(joint_command.get_velocity(joint));
331 break;
332 case JointStateVariable::ACCELERATIONS:
333 joint_command_values.push_back(joint_command.get_acceleration(joint));
334 break;
335 case JointStateVariable::TORQUES:
336 joint_command_values.push_back(joint_command.get_torque(joint));
337 break;
338 default:
339 break;
340 }
341 } catch (const state_representation::exceptions::JointNotFoundException& ex) {
343 }
344 }
345
346 if (joint_command_values.size() == joints_.size()) {
347 joint_command_values_.writeFromNonRT(joint_command_values);
348 new_joint_command_ready_ = true;
349 } else {
351 get_node()->get_logger(), *get_node()->get_clock(), 1000,
352 "Unable to set command values from provided joint command");
353 }
354}
355
356bool RobotControllerInterface::on_validate_parameter_callback(const std::shared_ptr<ParameterInterface>& parameter) {
357 if ((parameter->get_name() == "command_half_life" || parameter->get_name() == "command_rate_limit")
358 && parameter->get_parameter_value<double>() < 0.0) {
360 get_node()->get_logger(), "Parameter value of '%s' should be greater than 0", parameter->get_name().c_str());
361 return false;
362 }
363 return true;
364}
365
366}// namespace modulo_controllers
std::shared_ptr< state_representation::ParameterInterface > get_parameter(const std::string &name) const
Get a parameter by name.
T get_parameter_value(const std::string &name) const
Get a parameter value by name.
void add_parameter(const std::shared_ptr< state_representation::ParameterInterface > &parameter, const std::string &description, bool read_only=false)
Add a parameter.
virtual controller_interface::return_type write_command_interfaces(const rclcpp::Duration &period)
Write the command interfaces.
virtual controller_interface::return_type read_state_interfaces()
Read the state interfaces.
std::unordered_map< std::string, double > get_state_interfaces(const std::string &name) const
Get a map containing the state interfaces by name of the parent tag.
double get_state_interface(const std::string &name, const std::string &interface) const
Get the value of a state interface by name.
void set_command_interface(const std::string &name, const std::string &interface, double value)
Set the value of a command interface by name.
std::string hardware_name_
The hardware name provided by a parameter.
void add_command_interface(const std::string &name, const std::string &interface)
Add a command interface to the controller by name.
Base controller class that automatically associates joints with a JointState object.
std::string ft_sensor_name_
The name of a force torque sensor in the hardware description.
const state_representation::CartesianState & get_cartesian_state()
Access the Cartesian state object.
CallbackReturn on_activate() override
Activate the controller.
bool on_validate_parameter_callback(const std::shared_ptr< state_representation::ParameterInterface > &parameter) override
Parameter validation function to be redefined by derived controller classes.
const state_representation::JointState & get_joint_state()
Access the joint state object.
std::string ft_sensor_reference_frame_
The sensing reference frame.
const state_representation::CartesianWrench & get_ft_sensor()
Access the Cartesian wrench object.
std::shared_ptr< robot_model::Model > robot_
Robot model object generated from URDF.
void compute_cartesian_state()
Compute the Cartesian state from forward kinematics of the current joint state.
void set_joint_command(const state_representation::JointState &joint_command)
Set the joint command object.
CallbackReturn add_interfaces() override
Add interfaces like parameters, signals, services, and predicates to the controller.
std::string task_space_frame_
The frame in task space for forward kinematics calculations, if applicable.
CallbackReturn on_configure() override
Configure the controller.