29 #ifndef SCALED_JOINT_TRAJECTORY_CONTROLLER_HARDWARE_INTERFACE_ADAPTER_H_INCLUDED 30 #define SCALED_JOINT_TRAJECTORY_CONTROLLER_HARDWARE_INTERFACE_ADAPTER_H_INCLUDED 32 #include <joint_trajectory_controller/hardware_interface_adapter.h> 55 template <
class State>
66 joint_handles_ptr_ = &joint_handles;
73 if (!joint_handles_ptr_)
79 for (
auto& jh : *joint_handles_ptr_)
81 jh.setCommand(jh.getPosition());
93 const unsigned int n_joints = joint_handles_ptr_->size();
94 for (
unsigned int i = 0; i < n_joints; ++i)
96 (*joint_handles_ptr_)[i].setCommand(desired_state.position[i]);
115 template <
class State>
123 bool init(std::vector<scaled_controllers::ScaledJointHandle>& joint_handles,
ros::NodeHandle& controller_nh)
126 joint_handles_ptr_ = &joint_handles;
129 pids_.resize(joint_handles.size());
130 for (
unsigned int i = 0; i < pids_.size(); ++i)
137 if (!pids_[i]->
init(joint_nh))
139 ROS_WARN_STREAM(
"Failed to initialize PID gains from ROS parameter server.");
145 velocity_ff_.resize(joint_handles.size());
146 for (
unsigned int i = 0; i < velocity_ff_.size(); ++i)
148 controller_nh.
param(std::string(
"velocity_ff/") + joint_handles[i].
getName(), velocity_ff_[i], 0.0);
156 if (!joint_handles_ptr_)
162 for (
unsigned int i = 0; i < pids_.size(); ++i)
165 (*joint_handles_ptr_)[i].setCommand(0.0);
174 const State& state_error)
176 const unsigned int n_joints = joint_handles_ptr_->size();
179 if (!joint_handles_ptr_)
181 assert(n_joints == state_error.position.size());
182 assert(n_joints == state_error.velocity.size());
185 for (
unsigned int i = 0; i < n_joints; ++i)
187 const double command = (desired_state.velocity[i] * velocity_ff_[i]) +
188 pids_[i]->computeCommand(state_error.position[i], state_error.velocity[i], period);
189 (*joint_handles_ptr_)[i].setCommand(command);
194 typedef std::shared_ptr<control_toolbox::Pid>
PidPtr;
226 template <
class State>
232 #endif // ifndef SCALED_JOINT_TRAJECTORY_CONTROLLER_HARDWARE_INTERFACE_ADAPTER_H_INCLUDED std::vector< PidPtr > pids_
bool init(std::vector< scaled_controllers::ScaledJointHandle > &joint_handles, ros::NodeHandle &controller_nh)
bool init(std::vector< typename HardwareInterface::ResourceHandleType > &, ros::NodeHandle &)
ROSCONSOLE_CONSOLE_IMPL_DECL std::string getName(void *handle)
ClosedLoopHardwareInterfaceAdapter()
bool init(std::vector< scaled_controllers::ScaledJointHandle > &joint_handles, ros::NodeHandle &)
std::vector< scaled_controllers::ScaledJointHandle > * joint_handles_ptr_
std::shared_ptr< control_toolbox::Pid > PidPtr
void starting(const ros::Time &)
HardwareInterfaceAdapter()
bool param(const std::string ¶m_name, T ¶m_val, const T &default_val) const
void updateCommand(const ros::Time &, const ros::Duration &, const State &desired_state, const State &)
ROSLIB_DECL std::string command(const std::string &cmd)
void starting(const ros::Time &)
Helper base class template for closed loop HardwareInterfaceAdapter implementations.
void updateCommand(const ros::Time &, const ros::Duration &period, const State &desired_state, const State &state_error)
#define ROS_WARN_STREAM(args)
std::vector< double > velocity_ff_
void stopping(const ros::Time &)
std::vector< scaled_controllers::ScaledJointHandle > * joint_handles_ptr_
void stopping(const ros::Time &)