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

#include <srh_joint_muscle_valve_controller.hpp>

Inheritance diagram for controller::SrhJointMuscleValveController:
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)
 SrhJointMuscleValveController ()
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.

Public Attributes

unsigned int cmd_duration_ms_ [2]
int8_t cmd_valve_muscle_ [2]
int8_t cmd_valve_muscle_max_
int8_t cmd_valve_muscle_min_
unsigned int current_duration_ms_ [2]

Private Member Functions

int8_t clamp_command (int8_t cmd)
 enforce that the value of the received command is in the allowed range
void read_parameters ()
 read all the controller settings from the parameter server
void setCommandCB (const sr_robot_msgs::JointMuscleValveControllerCommandConstPtr &msg)

Private Attributes

boost::shared_ptr
< realtime_tools::RealtimePublisher
< sr_robot_msgs::JointMuscleValveControllerState > > 
controller_state_publisher_
ros::Subscriber sub_command_

Detailed Description

Definition at line 39 of file srh_joint_muscle_valve_controller.hpp.


Constructor & Destructor Documentation

Definition at line 45 of file srh_joint_muscle_valve_controller.cpp.


Member Function Documentation

enforce that the value of the received command is in the allowed range

Definition at line 304 of file srh_joint_muscle_valve_controller.cpp.

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

Reimplemented from controller::SrController.

Definition at line 143 of file srh_joint_muscle_valve_controller.cpp.

Implements controller::SrController.

Definition at line 51 of file srh_joint_muscle_valve_controller.cpp.

read all the controller settings from the parameter server

Definition at line 285 of file srh_joint_muscle_valve_controller.cpp.

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

Reimplemented from controller::SrController.

Definition at line 129 of file srh_joint_muscle_valve_controller.cpp.

void controller::SrhJointMuscleValveController::setCommandCB ( const sr_robot_msgs::JointMuscleValveControllerCommandConstPtr &  msg) [private]

Definition at line 290 of file srh_joint_muscle_valve_controller.cpp.

Reimplemented from controller::SrController.

Definition at line 109 of file srh_joint_muscle_valve_controller.cpp.

void controller::SrhJointMuscleValveController::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 147 of file srh_joint_muscle_valve_controller.cpp.


Member Data Documentation

Last duration commanded for the valve command for each muscle.

Definition at line 58 of file srh_joint_muscle_valve_controller.hpp.

Last commanded valve values for each muscle.

Definition at line 57 of file srh_joint_muscle_valve_controller.hpp.

Definition at line 62 of file srh_joint_muscle_valve_controller.hpp.

Definition at line 61 of file srh_joint_muscle_valve_controller.hpp.

boost::shared_ptr<realtime_tools::RealtimePublisher<sr_robot_msgs::JointMuscleValveControllerState> > controller::SrhJointMuscleValveController::controller_state_publisher_ [private]

Reimplemented from controller::SrController.

Definition at line 66 of file srh_joint_muscle_valve_controller.hpp.

Definition at line 59 of file srh_joint_muscle_valve_controller.hpp.

Reimplemented from controller::SrController.

Definition at line 68 of file srh_joint_muscle_valve_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