1#include "modulo_controllers/RobotControllerInterface.hpp"
3#include "ament_index_cpp/get_package_share_directory.hpp"
4#include <hardware_interface/types/hardware_interface_type_values.hpp>
6#include <state_representation/exceptions/JointNotFoundException.hpp>
8using namespace state_representation;
10namespace modulo_controllers {
12static const std::map<std::string, JointStateVariable> interface_map =
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}};
21 bool robot_model_required,
const std::string& control_type,
bool load_geometries)
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()) {
31 throw std::invalid_argument(
"Invalid control type");
38 "The frame name in the robot model to use for kinematics calculations (defaults to the last frame in the "
42 "If true, re-arrange the 'joints' parameter into a physically correct order according to the robot model");
45 "Optionally, the name of a force-torque sensor in the hardware interface");
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 "
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;
61 std::stringstream timestamp;
62 timestamp << std::time(
nullptr);
66 if (load_geometries_) {
68 return ament_index_cpp::get_package_share_directory(
package_name) +
"/";
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(),
82 if (robot_model_required_ &&
robot_ ==
nullptr) {
84 return CallbackReturn::ERROR;
94 get_node()->
get_logger(),
"Provided task space frame %s does not exist in the robot model!",
96 return CallbackReturn::ERROR;
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;
108 joints_ =
joints->get_parameter_value<std::vector<std::string>>();
112 if (joints_.size() !=
robot_->get_number_of_joints()) {
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());
131 return CallbackReturn::ERROR;
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());
142 previous_joint_command_values_ = std::vector<double>(joints_.size(), 0.0);
144 for (
const auto&
joint : joints_) {
156 "The 'ft_sensor_reference_frame' parameter cannot be empty if a force-torque sensor is specified!");
157 return CallbackReturn::ERROR;
163 get_node()->
get_logger(),
"The FT sensor reference frame '%s' does not exist on the robot model!",
165 return CallbackReturn::ERROR;
173 return CallbackReturn::SUCCESS;
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!",
190 return CallbackReturn::FAILURE;
196 return CallbackReturn::SUCCESS;
199controller_interface::return_type RobotControllerInterface::read_state_interfaces() {
201 if (
status != controller_interface::return_type::OK) {
205 if (joint_state_.get_size() > 0 && joint_state_.is_empty()) {
207 joint_state_.set_zero();
210 for (
const auto&
joint : joints_) {
215 }
catch (exceptions::JointNotFoundException&
ex) {
217 return controller_interface::return_type::ERROR;
220 if (!std::isfinite(
value)) {
224 return controller_interface::return_type::ERROR;
227 case JointStateVariable::POSITIONS:
230 case JointStateVariable::VELOCITIES:
233 case JointStateVariable::ACCELERATIONS:
236 case JointStateVariable::TORQUES:
249 ft_sensor_.set_wrench(
wrench);
252 return controller_interface::return_type::OK;
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();
263 new_joint_command_ready_ =
false;
266 for (std::size_t index = 0; index < joints_.size(); ++index) {
268 if (new_joint_command_ready_) {
275 previous_joint_command_values_.at(index) =
new_command;
276 }
else if (control_type_ != hardware_interface::HW_IF_POSITION) {
279 previous_joint_command_values_.at(index) =
new_command;
282 new_joint_command_ready_ =
false;
295 return cartesian_state_;
307 if (!ft_sensor_.is_empty() && (ft_sensor_.get_reference_frame() == cartesian_state_.get_name())) {
323 for (
const auto&
joint : joints_) {
325 switch (interface_map.at(control_type_)) {
326 case JointStateVariable::POSITIONS:
329 case JointStateVariable::VELOCITIES:
332 case JointStateVariable::ACCELERATIONS:
335 case JointStateVariable::TORQUES:
341 }
catch (
const state_representation::exceptions::JointNotFoundException&
ex) {
348 new_joint_command_ready_ =
true;
352 "Unable to set command values from provided joint command");
357 if ((
parameter->get_name() ==
"command_half_life" ||
parameter->get_name() ==
"command_rate_limit")
358 &&
parameter->get_parameter_value<
double>() < 0.0) {
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 > ¶meter, 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.
RobotControllerInterface()
Default constructor.
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 > ¶meter) 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.