30 #ifndef _SRH_MUSCLE_VALVE_CONTROLLER_HPP_ 31 #define _SRH_MUSCLE_VALVE_CONTROLLER_HPP_ 34 #include <sr_robot_msgs/JointMuscleValveControllerState.h> 35 #include <sr_robot_msgs/JointMuscleValveControllerCommand.h> 54 virtual void getGains(
double &p,
double &i,
double &
d,
double &i_max,
double &i_min);
56 virtual bool resetGains(std_srvs::Empty::Request &req, std_srvs::Empty::Response &resp);
74 void setCommandCB(
const sr_robot_msgs::JointMuscleValveControllerCommandConstPtr &msg);
virtual bool resetGains(std_srvs::Empty::Request &req, std_srvs::Empty::Response &resp)
A generic controller for the Shadow Robot EtherCAT hand's joints.
int8_t cmd_valve_muscle_[2]
int8_t clamp_command(int8_t cmd)
enforce that the value of the received command is in the allowed range
int8_t cmd_valve_muscle_min_
virtual void getGains(double &p, double &i, double &d, double &i_max, double &i_min)
void read_parameters()
read all the controller settings from the parameter server
unsigned int current_duration_ms_[2]
SrhJointMuscleValveController()
boost::shared_ptr< realtime_tools::RealtimePublisher< sr_robot_msgs::JointMuscleValveControllerState > > controller_state_publisher_
virtual void starting(const ros::Time &time)
unsigned int cmd_duration_ms_[2]
void setCommandCB(const sr_robot_msgs::JointMuscleValveControllerCommandConstPtr &msg)
int8_t cmd_valve_muscle_max_
bool init(ros_ethercat_model::RobotStateInterface *robot, ros::NodeHandle &n)
virtual void update(const ros::Time &time, const ros::Duration &period)
Issues commands to the joint. Should be called at regular intervals.
ros::Subscriber sub_command_