#include <srh_joint_muscle_valve_controller.hpp>

Public Member Functions | |
| virtual void | getGains (double &p, double &i, double &d, double &i_max, double &i_min) |
| bool | init (pr2_mechanism_model::RobotState *robot, const std::string &joint_name) |
| bool | init (pr2_mechanism_model::RobotState *robot, ros::NodeHandle &n) |
| virtual bool | resetGains (std_srvs::Empty::Request &req, std_srvs::Empty::Response &resp) |
| SrhJointMuscleValveController () | |
| virtual void | starting () |
| virtual void | update () |
| Issues commands to the joint. Should be called at regular intervals. | |
| virtual | ~SrhJointMuscleValveController () |
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_ |
Definition at line 39 of file srh_joint_muscle_valve_controller.hpp.
Definition at line 44 of file srh_joint_muscle_valve_controller.cpp.
Definition at line 51 of file srh_joint_muscle_valve_controller.cpp.
| int8_t controller::SrhJointMuscleValveController::clamp_command | ( | int8_t | cmd | ) | [private] |
enforce that the value of the received command is in the allowed range
Definition at line 337 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 167 of file srh_joint_muscle_valve_controller.cpp.
| bool controller::SrhJointMuscleValveController::init | ( | pr2_mechanism_model::RobotState * | robot, |
| const std::string & | joint_name | ||
| ) |
Definition at line 56 of file srh_joint_muscle_valve_controller.cpp.
| bool controller::SrhJointMuscleValveController::init | ( | pr2_mechanism_model::RobotState * | robot, |
| ros::NodeHandle & | n | ||
| ) | [virtual] |
Reimplemented from controller::SrController.
Definition at line 115 of file srh_joint_muscle_valve_controller.cpp.
| void controller::SrhJointMuscleValveController::read_parameters | ( | ) | [private] |
read all the controller settings from the parameter server
Definition at line 319 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 153 of file srh_joint_muscle_valve_controller.cpp.
| void controller::SrhJointMuscleValveController::setCommandCB | ( | const sr_robot_msgs::JointMuscleValveControllerCommandConstPtr & | msg | ) | [private] |
Definition at line 324 of file srh_joint_muscle_valve_controller.cpp.
| void controller::SrhJointMuscleValveController::starting | ( | ) | [virtual] |
Reimplemented from controller::SrController.
Definition at line 134 of file srh_joint_muscle_valve_controller.cpp.
| void controller::SrhJointMuscleValveController::update | ( | void | ) | [virtual] |
Issues commands to the joint. Should be called at regular intervals.
Reimplemented from controller::SrController.
Definition at line 171 of file srh_joint_muscle_valve_controller.cpp.
| unsigned int controller::SrhJointMuscleValveController::cmd_duration_ms_[2] |
Last duration commanded for the valve command for each muscle.
Definition at line 60 of file srh_joint_muscle_valve_controller.hpp.
Last commanded valve values for each muscle.
Definition at line 59 of file srh_joint_muscle_valve_controller.hpp.
Definition at line 64 of file srh_joint_muscle_valve_controller.hpp.
Definition at line 63 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 68 of file srh_joint_muscle_valve_controller.hpp.
| unsigned int controller::SrhJointMuscleValveController::current_duration_ms_[2] |
Definition at line 61 of file srh_joint_muscle_valve_controller.hpp.
Reimplemented from controller::SrController.
Definition at line 70 of file srh_joint_muscle_valve_controller.hpp.