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

#include <srh_mixed_position_velocity_controller.hpp>

Inheritance diagram for controller::SrhMixedPositionVelocityJointController:
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)
virtual void getGains_velocity (double &p, double &i, double &d, double &i_max, double &i_min)
bool init (pr2_mechanism_model::RobotState *robot, const std::string &joint_name, boost::shared_ptr< control_toolbox::Pid > pid_position, boost::shared_ptr< control_toolbox::Pid > pid_velocity)
bool init (pr2_mechanism_model::RobotState *robot, ros::NodeHandle &n)
virtual bool resetGains (std_srvs::Empty::Request &req, std_srvs::Empty::Response &resp)
bool setGains (sr_robot_msgs::SetMixedPositionVelocityPidGains::Request &req, sr_robot_msgs::SetMixedPositionVelocityPidGains::Response &resp)
 SrhMixedPositionVelocityJointController ()
virtual void starting ()
virtual void update ()
 Issues commands to the joint. Should be called at regular intervals.
virtual ~SrhMixedPositionVelocityJointController ()

Private Member Functions

void read_parameters ()
 read all the controller settings from the parameter server

Private Attributes

boost::shared_ptr
< realtime_tools::RealtimePublisher
< sr_robot_msgs::JointControllerState > > 
controller_state_publisher_
sr_deadband::HysteresisDeadband
< double > 
hysteresis_deadband
 We're using an hysteresis deadband.
double max_velocity_
 The values for the velocity demand saturation.
double min_velocity_
int motor_min_force_threshold
 smallest demand we can send to the motors
boost::shared_ptr
< control_toolbox::Pid
pid_controller_position_
boost::shared_ptr
< control_toolbox::Pid
pid_controller_velocity_
double position_deadband
 the deadband on the position demand
ros::ServiceServer serve_set_gains_

Detailed Description

Definition at line 39 of file srh_mixed_position_velocity_controller.hpp.


Constructor & Destructor Documentation

Definition at line 45 of file srh_mixed_position_velocity_controller.cpp.

Definition at line 51 of file srh_mixed_position_velocity_controller.cpp.


Member Function Documentation

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

Reimplemented from controller::SrController.

Definition at line 244 of file srh_mixed_position_velocity_controller.cpp.

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

Definition at line 248 of file srh_mixed_position_velocity_controller.cpp.

bool controller::SrhMixedPositionVelocityJointController::init ( pr2_mechanism_model::RobotState robot,
const std::string &  joint_name,
boost::shared_ptr< control_toolbox::Pid pid_position,
boost::shared_ptr< control_toolbox::Pid pid_velocity 
)

Definition at line 56 of file srh_mixed_position_velocity_controller.cpp.

Reimplemented from controller::SrController.

Definition at line 142 of file srh_mixed_position_velocity_controller.cpp.

read all the controller settings from the parameter server

Definition at line 398 of file srh_mixed_position_velocity_controller.cpp.

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

Reimplemented from controller::SrController.

Definition at line 221 of file srh_mixed_position_velocity_controller.cpp.

bool controller::SrhMixedPositionVelocityJointController::setGains ( sr_robot_msgs::SetMixedPositionVelocityPidGains::Request &  req,
sr_robot_msgs::SetMixedPositionVelocityPidGains::Response &  resp 
)

Definition at line 183 of file srh_mixed_position_velocity_controller.cpp.

Reimplemented from controller::SrController.

Definition at line 169 of file srh_mixed_position_velocity_controller.cpp.

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

Reimplemented from controller::SrController.

Definition at line 253 of file srh_mixed_position_velocity_controller.cpp.


Member Data Documentation

Reimplemented from controller::SrController.

Definition at line 68 of file srh_mixed_position_velocity_controller.hpp.

We're using an hysteresis deadband.

Reimplemented from controller::SrController.

Definition at line 86 of file srh_mixed_position_velocity_controller.hpp.

The values for the velocity demand saturation.

Definition at line 71 of file srh_mixed_position_velocity_controller.hpp.

Definition at line 71 of file srh_mixed_position_velocity_controller.hpp.

smallest demand we can send to the motors

Definition at line 92 of file srh_mixed_position_velocity_controller.hpp.

Internal PID controller for the position loop.

Definition at line 64 of file srh_mixed_position_velocity_controller.hpp.

Internal PID controller for the velocity loop.

Definition at line 65 of file srh_mixed_position_velocity_controller.hpp.

the deadband on the position demand

Definition at line 83 of file srh_mixed_position_velocity_controller.hpp.

Reimplemented from controller::SrController.

Definition at line 80 of file srh_mixed_position_velocity_controller.hpp.


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


sr_mechanism_controllers
Author(s): Ugo Cupcic
autogenerated on Fri Aug 28 2015 13:09:56