3#include <realtime_tools/realtime_buffer.h>
5#include <robot_model/Model.hpp>
6#include <state_representation/space/cartesian/CartesianState.hpp>
7#include <state_representation/space/cartesian/CartesianWrench.hpp>
8#include <state_representation/space/joint/JointState.hpp>
10#include "modulo_controllers/ControllerInterface.hpp"
12namespace modulo_controllers {
97 std::shared_ptr<robot_model::Model>
robot_;
108 controller_interface::return_type read_state_interfaces()
final;
116 std::
vector<std::
string> joints_;
117 std::
string control_type_;
119 bool robot_model_required_;
120 bool load_geometries_;
122 new_joint_command_ready_;
124 command_decay_factor_;
129 std::
vector<
double> previous_joint_command_values_;
131 state_representation::
JointState joint_state_;
T get_parameter_value(const std::string &name) const
Get a parameter value 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.