#include <sr_controller.hpp>
Public Member Functions | |
virtual void | getGains (double &p, double &i, double &d, double &i_max, double &i_min) |
std::string | getJointName () |
virtual bool | init (ros_ethercat_model::RobotStateInterface *robot, ros::NodeHandle &n)=0 |
virtual bool | resetGains (std_srvs::Empty::Request &req, std_srvs::Empty::Response &resp) |
SrController () | |
virtual void | starting (const ros::Time &time) |
virtual void | update (const ros::Time &time, const ros::Duration &period)=0 |
Issues commands to the joint. Should be called at regular intervals. More... | |
virtual | ~SrController () |
Public Member Functions inherited from controller_interface::Controller< ros_ethercat_model::RobotStateInterface > | |
Controller () | |
virtual bool | init (ros_ethercat_model::RobotStateInterface *, ros::NodeHandle &, ros::NodeHandle &) |
virtual | ~Controller () |
Public Member Functions inherited from controller_interface::ControllerBase | |
ControllerBase () | |
bool | isRunning () |
bool | isRunning () |
bool | startRequest (const ros::Time &time) |
bool | startRequest (const ros::Time &time) |
virtual void | stopping (const ros::Time &) |
virtual void | stopping (const ros::Time &) |
bool | stopRequest (const ros::Time &time) |
bool | stopRequest (const ros::Time &time) |
void | updateRequest (const ros::Time &time, const ros::Duration &period) |
void | updateRequest (const ros::Time &time, const ros::Duration &period) |
virtual | ~ControllerBase () |
Public Attributes | |
double | command_ |
bool | has_j2 |
ros_ethercat_model::JointState * | joint_state_ |
ros_ethercat_model::JointState * | joint_state_2 |
Public Attributes inherited from controller_interface::ControllerBase | |
CONSTRUCTED | |
INITIALIZED | |
RUNNING | |
enum controller_interface::ControllerBase:: { ... } | state_ |
Protected Member Functions | |
void | after_init () |
call this function at the end of the init function in the inheriting classes. More... | |
double | clamp_command (double cmd, double min_cmd, double max_cmd) |
virtual double | clamp_command (double cmd) |
void | get_joints_states_1_2 () |
void | get_min_max (urdf::Model model, std::string joint_name) |
bool | is_joint_0 () |
void | maxForceFactorCB (const std_msgs::Float64ConstPtr &msg) |
virtual void | setCommandCB (const std_msgs::Float64ConstPtr &msg) |
set the command from a topic More... | |
Protected Member Functions inherited from controller_interface::Controller< ros_ethercat_model::RobotStateInterface > | |
std::string | getHardwareInterfaceType () const |
virtual bool | initRequest (hardware_interface::RobotHW *robot_hw, ros::NodeHandle &root_nh, ros::NodeHandle &controller_nh, ClaimedResources &claimed_resources) |
Protected Attributes | |
boost::scoped_ptr< realtime_tools::RealtimePublisher< control_msgs::JointControllerState > > | controller_state_publisher_ |
double | eff_max_ |
double | eff_min_ |
Min and max range of the effort, used to clamp the command. More... | |
boost::scoped_ptr< sr_friction_compensation::SrFrictionCompensator > | friction_compensator |
int | friction_deadband |
the deadband for the friction compensation algorithm More... | |
sr_deadband::HysteresisDeadband< double > | hysteresis_deadband |
We're using an hysteresis deadband. More... | |
bool | initialized_ |
std::string | joint_name_ |
int | loop_count_ |
double | max_ |
double | max_force_demand |
clamps the force demand to this value More... | |
double | max_force_factor_ |
double | min_ |
Min and max range of the joint, used to clamp the command. More... | |
ros::NodeHandle | n_tilde_ |
ros::NodeHandle | node_ |
ros_ethercat_model::RobotState * | robot_ |
ros::ServiceServer | serve_reset_gains_ |
ros::ServiceServer | serve_set_gains_ |
ros::Subscriber | sub_command_ |
ros::Subscriber | sub_max_force_factor_ |
double | vel_max_ |
double | vel_min_ |
Min and max range of the velocity, used to clamp the command. More... | |
Additional Inherited Members | |
Public Types inherited from controller_interface::ControllerBase | |
typedef std::vector< hardware_interface::InterfaceResources > | ClaimedResources |
Definition at line 54 of file sr_controller.hpp.
controller::SrController::SrController | ( | ) |
Definition at line 40 of file sr_controller.cpp.
|
virtual |
Definition at line 61 of file sr_controller.cpp.
|
protected |
call this function at the end of the init function in the inheriting classes.
Definition at line 89 of file sr_controller.cpp.
|
protected |
Clamps the command to the correct range (between min_cmd and max_cmd).
cmd | the command we want to clamp |
min_cmd | the min to clamp to |
max_cmd | the max to clamp to |
Definition at line 133 of file sr_controller.cpp.
|
protectedvirtual |
Clamps the command to the correct range (between angular min and max).
cmd | the command we want to clamp |
Reimplemented in controller::SrhJointVelocityController, and controller::SrhEffortJointController.
Definition at line 146 of file sr_controller.cpp.
|
protected |
Definition at line 77 of file sr_controller.cpp.
|
protected |
Reads the min and max from the robot model for the current joint.
model | the urdf description of the robot |
joint_name | the name of the joint |
Definition at line 101 of file sr_controller.cpp.
|
inlinevirtual |
Reimplemented in controller::SrhJointMuscleValveController, controller::SrhJointVariablePidPositionController, controller::SrhMixedPositionVelocityJointController, controller::SrhJointVelocityController, controller::SrhEffortJointController, controller::SrhJointPositionController, and controller::SrhMuscleJointPositionController.
Definition at line 78 of file sr_controller.hpp.
std::string controller::SrController::getJointName | ( | ) |
Definition at line 96 of file sr_controller.cpp.
|
pure virtual |
Reimplemented from controller_interface::Controller< ros_ethercat_model::RobotStateInterface >.
Implemented in controller::SrhExampleController, controller::SrhSyntouchController, controller::SrhJointMuscleValveController, controller::SrhJointVariablePidPositionController, controller::SrhMixedPositionVelocityJointController, controller::SrhJointVelocityController, controller::SrhEffortJointController, controller::SrhJointPositionController, and controller::SrhMuscleJointPositionController.
|
protected |
Definition at line 66 of file sr_controller.cpp.
|
protected |
Callback function for the max force factor topic
msg | the message receiver over the topic |
Definition at line 151 of file sr_controller.cpp.
|
inlinevirtual |
Reimplemented in controller::SrhMixedPositionVelocityJointController, controller::SrhJointMuscleValveController, controller::SrhJointVariablePidPositionController, controller::SrhJointVelocityController, controller::SrhEffortJointController, controller::SrhJointPositionController, and controller::SrhMuscleJointPositionController.
Definition at line 73 of file sr_controller.hpp.
|
inlineprotectedvirtual |
set the command from a topic
Reimplemented in controller::SrhMixedPositionVelocityJointController, controller::SrhJointVariablePidPositionController, controller::SrhMuscleJointPositionController, controller::SrhJointVelocityController, controller::SrhJointPositionController, and controller::SrhEffortJointController.
Definition at line 154 of file sr_controller.hpp.
|
inlinevirtual |
Reimplemented from controller_interface::ControllerBase.
Reimplemented in controller::SrhExampleController, controller::SrhSyntouchController, controller::SrhJointMuscleValveController, controller::SrhJointVariablePidPositionController, controller::SrhMixedPositionVelocityJointController, controller::SrhJointVelocityController, controller::SrhEffortJointController, controller::SrhJointPositionController, and controller::SrhMuscleJointPositionController.
Definition at line 64 of file sr_controller.hpp.
|
pure virtual |
Issues commands to the joint. Should be called at regular intervals.
Implements controller_interface::ControllerBase.
Implemented in controller::SrhExampleController, controller::SrhSyntouchController, controller::SrhJointMuscleValveController, controller::SrhJointVariablePidPositionController, controller::SrhMixedPositionVelocityJointController, controller::SrhJointVelocityController, controller::SrhEffortJointController, controller::SrhJointPositionController, and controller::SrhMuscleJointPositionController.
double controller::SrController::command_ |
Last commanded position.
Definition at line 90 of file sr_controller.hpp.
|
protected |
Definition at line 149 of file sr_controller.hpp.
|
protected |
Definition at line 138 of file sr_controller.hpp.
|
protected |
Min and max range of the effort, used to clamp the command.
Definition at line 138 of file sr_controller.hpp.
|
protected |
Definition at line 151 of file sr_controller.hpp.
|
protected |
the deadband for the friction compensation algorithm
Definition at line 165 of file sr_controller.hpp.
bool controller::SrController::has_j2 |
true if this is a joint 0.
Definition at line 88 of file sr_controller.hpp.
|
protected |
We're using an hysteresis deadband.
Definition at line 168 of file sr_controller.hpp.
|
protected |
Definition at line 141 of file sr_controller.hpp.
|
protected |
Definition at line 146 of file sr_controller.hpp.
ros_ethercat_model::JointState* controller::SrController::joint_state_ |
Joint we're controlling.
Definition at line 84 of file sr_controller.hpp.
ros_ethercat_model::JointState* controller::SrController::joint_state_2 |
2ndJoint we're controlling if joint 0.
Definition at line 86 of file sr_controller.hpp.
|
protected |
Definition at line 140 of file sr_controller.hpp.
|
protected |
Definition at line 134 of file sr_controller.hpp.
|
protected |
clamps the force demand to this value
Definition at line 163 of file sr_controller.hpp.
|
protected |
Definition at line 174 of file sr_controller.hpp.
|
protected |
Min and max range of the joint, used to clamp the command.
Definition at line 134 of file sr_controller.hpp.
|
protected |
Definition at line 145 of file sr_controller.hpp.
|
protected |
Definition at line 145 of file sr_controller.hpp.
|
protected |
Pointer to robot structure.
Definition at line 142 of file sr_controller.hpp.
|
protected |
Definition at line 160 of file sr_controller.hpp.
|
protected |
Definition at line 159 of file sr_controller.hpp.
|
protected |
Definition at line 158 of file sr_controller.hpp.
|
protected |
Definition at line 175 of file sr_controller.hpp.
|
protected |
Definition at line 136 of file sr_controller.hpp.
|
protected |
Min and max range of the velocity, used to clamp the command.
Definition at line 136 of file sr_controller.hpp.