Public Member Functions | Public Attributes | Protected Member Functions | Protected Attributes
controller::SrController Class Reference

#include <sr_controller.hpp>

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

List of all members.

Public Member Functions

void getCommand (double &cmd)
 Get latest position command to the joint: revolute (angle) and prismatic (position).
virtual void getGains (double &p, double &i, double &d, double &i_max, double &i_min)
std::string getJointName ()
virtual bool init (pr2_mechanism_model::RobotState *robot, ros::NodeHandle &n)
virtual bool resetGains (std_srvs::Empty::Request &req, std_srvs::Empty::Response &resp)
void setCommand (double cmd)
 Give set position of the joint for next update: revolute (angle) and prismatic (position)
virtual void setCommandCB (const std_msgs::Float64ConstPtr &msg)
 SrController ()
virtual void starting ()
virtual void update ()
 Issues commands to the joint. Should be called at regular intervals.
virtual ~SrController ()

Public Attributes

double command_
ros::Duration dt_
bool has_j2
pr2_mechanism_model::JointStatejoint_state_
pr2_mechanism_model::JointStatejoint_state_2

Protected Member Functions

void after_init ()
 call this function at the end of the init function in the inheriting classes.
double clamp_command (double cmd)
void get_min_max (urdf::Model model, std::string joint_name)
void maxForceFactorCB (const std_msgs::Float64ConstPtr &msg)

Protected Attributes

boost::scoped_ptr
< realtime_tools::RealtimePublisher
< pr2_controllers_msgs::JointControllerState > > 
controller_state_publisher_
boost::shared_ptr
< sr_friction_compensation::SrFrictionCompensator
friction_compensator
int friction_deadband
 the deadband for the friction compensation algorithm
sr_deadband::HysteresisDeadband
< double > 
hysteresis_deadband
 We're using an hysteresis deadband.
bool initialized_
ros::Time last_time_
int loop_count_
double max_
double max_force_demand
 clamps the force demand to this value
double max_force_factor_
double min_
 Min and max range of the joint, used to clamp the command.
ros::NodeHandle n_tilde_
ros::NodeHandle node_
pr2_mechanism_model::RobotStaterobot_
ros::ServiceServer serve_reset_gains_
ros::ServiceServer serve_set_gains_
ros::Subscriber sub_command_
ros::Subscriber sub_max_force_factor_

Detailed Description

Definition at line 53 of file sr_controller.hpp.


Constructor & Destructor Documentation

Definition at line 39 of file sr_controller.cpp.

Definition at line 48 of file sr_controller.cpp.


Member Function Documentation

call this function at the end of the init function in the inheriting classes.

Definition at line 53 of file sr_controller.cpp.

double controller::SrController::clamp_command ( double  cmd) [protected]

Clamps the command to the correct range (between min and max).

Parameters:
cmdthe command we want to clamp
Returns:
the clamped command

Definition at line 124 of file sr_controller.cpp.

void controller::SrController::get_min_max ( urdf::Model  model,
std::string  joint_name 
) [protected]

Reads the min and max from the robot model for the current joint.

Parameters:
modelthe urdf description of the robot
joint_namethe name of the joint

Definition at line 102 of file sr_controller.cpp.

void controller::SrController::getCommand ( double &  cmd)

Get latest position command to the joint: revolute (angle) and prismatic (position).

Definition at line 72 of file sr_controller.cpp.

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

Definition at line 60 of file sr_controller.cpp.

void controller::SrController::maxForceFactorCB ( const std_msgs::Float64ConstPtr &  msg) [protected]

Callback function for the max force factor topic

Parameters:
msgthe message receiver over the topic

Definition at line 135 of file sr_controller.cpp.

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

Give set position of the joint for next update: revolute (angle) and prismatic (position)

Parameters:
cmdthe received angle

Definition at line 66 of file sr_controller.cpp.

void controller::SrController::setCommandCB ( const std_msgs::Float64ConstPtr &  msg) [virtual]

Definition at line 77 of file sr_controller.cpp.

void controller::SrController::update ( void  ) [virtual]

Member Data Documentation

Last commanded position.

Definition at line 91 of file sr_controller.hpp.

boost::scoped_ptr< realtime_tools::RealtimePublisher< pr2_controllers_msgs::JointControllerState> > controller::SrController::controller_state_publisher_ [protected]

Definition at line 90 of file sr_controller.hpp.

Definition at line 130 of file sr_controller.hpp.

the deadband for the friction compensation algorithm

Definition at line 139 of file sr_controller.hpp.

true if this is a joint 0.

Definition at line 89 of file sr_controller.hpp.

Definition at line 120 of file sr_controller.hpp.

Joint we're controlling.

Definition at line 87 of file sr_controller.hpp.

2ndJoint we're controlling if joint 0.

Definition at line 88 of file sr_controller.hpp.

Last time stamp of update.

Definition at line 122 of file sr_controller.hpp.

Definition at line 119 of file sr_controller.hpp.

double controller::SrController::max_ [protected]

Definition at line 117 of file sr_controller.hpp.

clamps the force demand to this value

Reimplemented in controller::SrhMuscleJointPositionController, and controller::SrhJointPositionController.

Definition at line 137 of file sr_controller.hpp.

Definition at line 147 of file sr_controller.hpp.

double controller::SrController::min_ [protected]

Min and max range of the joint, used to clamp the command.

Definition at line 117 of file sr_controller.hpp.

Definition at line 124 of file sr_controller.hpp.

Definition at line 124 of file sr_controller.hpp.

Pointer to robot structure.

Definition at line 121 of file sr_controller.hpp.

Definition at line 134 of file sr_controller.hpp.

Reimplemented in controller::SrhMixedPositionVelocityJointController.

Definition at line 133 of file sr_controller.hpp.

Reimplemented in controller::SrhJointMuscleValveController.

Definition at line 132 of file sr_controller.hpp.

Definition at line 148 of file sr_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