31 #ifndef GRIPPER_ACTION_CONTROLLER_HARDWARE_INTERFACE_ADAPTER_H 32 #define GRIPPER_ACTION_CONTROLLER_HARDWARE_INTERFACE_ADAPTER_H 38 #include <boost/shared_ptr.hpp> 53 template <
class HardwareInterface>
67 double desired_position,
68 double desired_velocity,
69 double error_position,
70 double error_velocity,
71 double max_allowed_effort) {
return 0.0;}
87 joint_handle_ptr_ = &joint_handle;
97 double desired_position,
98 double desired_velocity,
99 double error_position,
100 double error_velocity,
101 double max_allowed_effort)
104 (*joint_handle_ptr_).setCommand(desired_position);
105 return max_allowed_effort;
137 joint_handle_ptr_ = &joint_handle;
144 if (!pid_->init(joint_nh))
146 ROS_WARN_STREAM(
"Failed to initialize PID gains from ROS parameter server.");
155 if (!joint_handle_ptr_)
161 (*joint_handle_ptr_).setCommand(0.0);
168 double desired_position,
169 double desired_velocity,
170 double error_position,
171 double error_velocity,
172 double max_allowed_effort)
175 if (!joint_handle_ptr_) {
return 0.0;}
178 double command = pid_->computeCommand(error_position, error_velocity, period);
179 command = std::min<double>(fabs(max_allowed_effort), std::max<double>(-fabs(max_allowed_effort), command));
180 (*joint_handle_ptr_).setCommand(command);
190 #endif // header guard bool init(hardware_interface::JointHandle &joint_handle, ros::NodeHandle &controller_nh)
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)
boost::shared_ptr< control_toolbox::Pid > PidPtr
std::string getName() const
void stopping(const ros::Time &time)
void starting(const ros::Time &time)
hardware_interface::JointHandle * joint_handle_ptr_
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)
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_
void stopping(const ros::Time &time)
void starting(const ros::Time &time)
ROSLIB_DECL std::string command(const std::string &cmd)
HardwareInterfaceAdapter()
HardwareInterfaceAdapter()
#define ROS_WARN_STREAM(args)
void starting(const ros::Time &time)
Helper class to simplify integrating the GripperActionController with different hardware interfaces...
bool init(hardware_interface::JointHandle &joint_handle, ros::NodeHandle &controller_nh)
void stopping(const ros::Time &time)