Go to the documentation of this file.
52 template <
class HardwareInterface>
66 double desired_position,
67 double desired_velocity,
68 double error_position,
69 double error_velocity,
70 double max_allowed_effort) {
return 0.0;}
86 joint_handle_ptr_ = &joint_handle;
96 double desired_position,
97 double desired_velocity,
98 double error_position,
99 double error_velocity,
100 double max_allowed_effort)
103 (*joint_handle_ptr_).setCommand(desired_position);
104 return max_allowed_effort;
136 joint_handle_ptr_ = &joint_handle;
143 if (!pid_->init(joint_nh))
145 ROS_WARN_STREAM(
"Failed to initialize PID gains from ROS parameter server.");
154 if (!joint_handle_ptr_)
160 (*joint_handle_ptr_).setCommand(0.0);
167 double desired_position,
168 double desired_velocity,
169 double error_position,
170 double error_velocity,
171 double max_allowed_effort)
174 if (!joint_handle_ptr_) {
return 0.0;}
177 double command = pid_->computeCommand(error_position, error_velocity, period);
178 command = std::min<double>(fabs(max_allowed_effort), std::max<double>(-fabs(max_allowed_effort),
command));
179 (*joint_handle_ptr_).setCommand(
command);
184 typedef std::shared_ptr<control_toolbox::Pid>
PidPtr;
void stopping(const ros::Time &time)
double updateCommand(const ros::Time &, const ros::Duration &period, double desired_position, double desired_velocity, double error_position, double error_velocity, double max_allowed_effort)
ROSLIB_DECL std::string command(const std::string &cmd)
bool init(hardware_interface::JointHandle &joint_handle, ros::NodeHandle &controller_nh)
double updateCommand(const ros::Time &, const ros::Duration &period, double desired_position, double desired_velocity, double error_position, double error_velocity, double max_allowed_effort)
hardware_interface::JointHandle * joint_handle_ptr_
hardware_interface::JointHandle * joint_handle_ptr_
void starting(const ros::Time &time)
#define ROS_WARN_STREAM(args)
void starting(const ros::Time &time)
void stopping(const ros::Time &time)
double updateCommand(const ros::Time &time, const ros::Duration &period, double desired_position, double desired_velocity, double error_position, double error_velocity, double max_allowed_effort)
HardwareInterfaceAdapter()
std::string getName() const
void starting(const ros::Time &time)
bool init(hardware_interface::JointHandle &joint_handle, ros::NodeHandle &controller_nh)
Helper class to simplify integrating the GripperActionController with different hardware interfaces.
HardwareInterfaceAdapter()
std::shared_ptr< control_toolbox::Pid > PidPtr
void stopping(const ros::Time &time)
bool init(hardware_interface::JointHandle &joint_handle, ros::NodeHandle &controller_nh)