30 #ifndef SRH_MIXED_POSITION_VELOCITY_CONTROLLER_H 31 #define SRH_MIXED_POSITION_VELOCITY_CONTROLLER_H 34 #include <sr_robot_msgs/SetMixedPositionVelocityPidGains.h> 35 #include <sr_robot_msgs/JointControllerState.h> 54 virtual void getGains(
double &p,
double &i,
double &
d,
double &i_max,
double &i_min);
56 virtual void getGains_velocity(
double &p,
double &i,
double &d,
double &i_max,
double &i_min);
58 virtual bool resetGains(std_srvs::Empty::Request &req, std_srvs::Empty::Response &resp);
60 bool setGains(sr_robot_msgs::SetMixedPositionVelocityPidGains::Request &req,
61 sr_robot_msgs::SetMixedPositionVelocityPidGains::Response &resp);
82 #ifdef DEBUG_PUBLISHER 100 void setCommandCB(
const std_msgs::Float64ConstPtr &msg);
bool prev_in_deadband_
Stores if was previously in the deadband.
virtual void update(const ros::Time &time, const ros::Duration &period)
Issues commands to the joint. Should be called at regular intervals.
double maintained_command_
A generic controller for the Shadow Robot EtherCAT hand's joints.
void setCommandCB(const std_msgs::Float64ConstPtr &msg)
set the position target from a topic
void read_parameters()
read all the controller settings from the parameter server
virtual void getGains(double &p, double &i, double &d, double &i_max, double &i_min)
virtual bool resetGains(std_srvs::Empty::Request &req, std_srvs::Empty::Response &resp)
boost::scoped_ptr< control_toolbox::Pid > pid_controller_velocity_
Internal PID controller for the velocity loop.
bool init(ros_ethercat_model::RobotStateInterface *robot, ros::NodeHandle &n)
virtual void getGains_velocity(double &p, double &i, double &d, double &i_max, double &i_min)
bool override_to_current_effort_
Override commanded_effort to current effort when in deadband.
double position_deadband
the deadband on the position demand
SrhMixedPositionVelocityJointController()
sr_deadband::HysteresisDeadband< double > hysteresis_deadband
We're using an hysteresis deadband.
ros::ServiceServer serve_set_gains_
virtual void starting(const ros::Time &time)
boost::scoped_ptr< control_toolbox::Pid > pid_controller_position_
Internal PID controller for the position loop.
int motor_min_force_threshold
smallest demand we can send to the motors
bool setGains(sr_robot_msgs::SetMixedPositionVelocityPidGains::Request &req, sr_robot_msgs::SetMixedPositionVelocityPidGains::Response &resp)
double max_velocity_
The values for the velocity demand saturation.
boost::scoped_ptr< realtime_tools::RealtimePublisher< sr_robot_msgs::JointControllerState > > controller_state_publisher_