Public Member Functions | Private Member Functions | Private Attributes
controller::SrhMuscleJointPositionController Class Reference

#include <srh_muscle_joint_position_controller.hpp>

Inheritance diagram for controller::SrhMuscleJointPositionController:
Inheritance graph
[legend]

List of all members.

Public Member Functions

virtual void getGains (double &p, double &i, double &d, double &i_max, double &i_min)
bool init (ros_ethercat_model::RobotState *robot, ros::NodeHandle &n)
virtual bool resetGains (std_srvs::Empty::Request &req, std_srvs::Empty::Response &resp)
bool setGains (sr_robot_msgs::SetPidGains::Request &req, sr_robot_msgs::SetPidGains::Response &resp)
 SrhMuscleJointPositionController ()
virtual void starting (const ros::Time &time)
virtual void update (const ros::Time &time, const ros::Duration &period)
 Issues commands to the joint. Should be called at regular intervals.

Private Member Functions

void read_parameters ()
 read all the controller settings from the parameter server
void resetJointState ()
void setCommandCB (const std_msgs::Float64ConstPtr &msg)
 set the position target from a topic

Private Attributes

int command_acc_
 Command accumulator, time to keep the valves open/shut, sign gives the direction.
boost::scoped_ptr
< realtime_tools::RealtimePublisher
< sr_robot_msgs::JointMusclePositionControllerState > > 
controller_state_publisher_
sr_deadband::HysteresisDeadband
< double > 
hysteresis_deadband
 We're using an hysteresis deadband.
boost::scoped_ptr
< control_toolbox::Pid
pid_controller_position_
double position_deadband
 the position deadband value used in the hysteresis_deadband

Detailed Description

Definition at line 36 of file srh_muscle_joint_position_controller.hpp.


Constructor & Destructor Documentation

Definition at line 43 of file srh_muscle_joint_position_controller.cpp.


Member Function Documentation

void controller::SrhMuscleJointPositionController::getGains ( double &  p,
double &  i,
double &  d,
double &  i_max,
double &  i_min 
) [virtual]

Reimplemented from controller::SrController.

Definition at line 160 of file srh_muscle_joint_position_controller.cpp.

Implements controller::SrController.

Definition at line 48 of file srh_muscle_joint_position_controller.cpp.

read all the controller settings from the parameter server

Definition at line 330 of file srh_muscle_joint_position_controller.cpp.

bool controller::SrhMuscleJointPositionController::resetGains ( std_srvs::Empty::Request &  req,
std_srvs::Empty::Response &  resp 
) [virtual]

Reimplemented from controller::SrController.

Definition at line 143 of file srh_muscle_joint_position_controller.cpp.

Definition at line 344 of file srh_muscle_joint_position_controller.cpp.

void controller::SrhMuscleJointPositionController::setCommandCB ( const std_msgs::Float64ConstPtr &  msg) [private, virtual]

set the position target from a topic

Reimplemented from controller::SrController.

Definition at line 337 of file srh_muscle_joint_position_controller.cpp.

bool controller::SrhMuscleJointPositionController::setGains ( sr_robot_msgs::SetPidGains::Request &  req,
sr_robot_msgs::SetPidGains::Response &  resp 
)

Definition at line 121 of file srh_muscle_joint_position_controller.cpp.

Reimplemented from controller::SrController.

Definition at line 109 of file srh_muscle_joint_position_controller.cpp.

void controller::SrhMuscleJointPositionController::update ( const ros::Time time,
const ros::Duration period 
) [virtual]

Issues commands to the joint. Should be called at regular intervals.

Implements controller::SrController.

Definition at line 165 of file srh_muscle_joint_position_controller.cpp.


Member Data Documentation

Command accumulator, time to keep the valves open/shut, sign gives the direction.

Definition at line 67 of file srh_muscle_joint_position_controller.hpp.

boost::scoped_ptr<realtime_tools::RealtimePublisher<sr_robot_msgs::JointMusclePositionControllerState> > controller::SrhMuscleJointPositionController::controller_state_publisher_ [private]

Reimplemented from controller::SrController.

Definition at line 58 of file srh_muscle_joint_position_controller.hpp.

We're using an hysteresis deadband.

Reimplemented from controller::SrController.

Definition at line 64 of file srh_muscle_joint_position_controller.hpp.

Internal PID controller for the position loop.

Definition at line 55 of file srh_muscle_joint_position_controller.hpp.

the position deadband value used in the hysteresis_deadband

Definition at line 61 of file srh_muscle_joint_position_controller.hpp.


The documentation for this class was generated from the following files:


sr_mechanism_controllers
Author(s): Ugo Cupcic
autogenerated on Fri Aug 21 2015 12:26:14