#include <RobotController.h>
Public Member Functions | |
void | addJoint (physics::JointPtr _jointPtr, bool advancedMode=false) |
void | addJointDependency (std::string _childName, std::string _parentName, double factor) |
const r2_msgs::JointStatus & | getJointStatus (const std::string &name) const |
void | publishJointStatuses (ros::Publisher &rosPub) const |
RobotController (physics::ModelPtr _modelPtr) | |
void | setJointControl (const r2_msgs::JointControl::ConstPtr &msg) |
void | setJointEffortTarget (const std::string &name, double target) |
void | setJointPositions (std::map< std::string, double > posMap) |
void | setJointPosTarget (const std::string &name, double target) |
void | setJointVelTarget (const std::string &name, double target) |
void | setPosPid (const std::string &name, double _p=0.0, double _i=0.0, double _d=0.0, double _imax=0.0, double _imin=0.0, double _cmdMax=0.0, double _cmdMin=0.0) |
void | setVelPid (const std::string &name, double _p=0.0, double _i=0.0, double _d=0.0, double _imax=0.0, double _imin=0.0, double _cmdMax=0.0, double _cmdMin=0.0) |
void | update () |
~RobotController () | |
Private Types | |
typedef std::multimap < std::string, std::pair < std::string, double > > | dependenciesType |
Private Attributes | |
dependenciesType | dependencies |
std::map< std::string, JointControllerPtr > | joints |
physics::ModelPtr | modelPtr |
common::Time | prevUpdateTime |
Definition at line 20 of file RobotController.h.
typedef std::multimap<std::string, std::pair<std::string, double> > gazebo::RobotController::dependenciesType [private] |
Definition at line 58 of file RobotController.h.
RobotController::RobotController | ( | physics::ModelPtr | _modelPtr | ) |
Definition at line 14 of file RobotController.cpp.
Definition at line 20 of file RobotController.cpp.
void RobotController::addJoint | ( | physics::JointPtr | _jointPtr, |
bool | advancedMode = false |
||
) |
Definition at line 24 of file RobotController.cpp.
void RobotController::addJointDependency | ( | std::string | _childName, |
std::string | _parentName, | ||
double | factor | ||
) |
Definition at line 31 of file RobotController.cpp.
const r2_msgs::JointStatus & RobotController::getJointStatus | ( | const std::string & | name | ) | const |
Definition at line 185 of file RobotController.cpp.
void RobotController::publishJointStatuses | ( | ros::Publisher & | rosPub | ) | const |
Definition at line 207 of file RobotController.cpp.
void RobotController::setJointControl | ( | const r2_msgs::JointControl::ConstPtr & | msg | ) |
Definition at line 164 of file RobotController.cpp.
void RobotController::setJointEffortTarget | ( | const std::string & | name, |
double | target | ||
) |
Definition at line 145 of file RobotController.cpp.
void RobotController::setJointPositions | ( | std::map< std::string, double > | posMap | ) |
Definition at line 72 of file RobotController.cpp.
void RobotController::setJointPosTarget | ( | const std::string & | name, |
double | target | ||
) |
Definition at line 109 of file RobotController.cpp.
void RobotController::setJointVelTarget | ( | const std::string & | name, |
double | target | ||
) |
Definition at line 127 of file RobotController.cpp.
void RobotController::setPosPid | ( | const std::string & | name, |
double | _p = 0.0 , |
||
double | _i = 0.0 , |
||
double | _d = 0.0 , |
||
double | _imax = 0.0 , |
||
double | _imin = 0.0 , |
||
double | _cmdMax = 0.0 , |
||
double | _cmdMin = 0.0 |
||
) |
Definition at line 47 of file RobotController.cpp.
void RobotController::setVelPid | ( | const std::string & | name, |
double | _p = 0.0 , |
||
double | _i = 0.0 , |
||
double | _d = 0.0 , |
||
double | _imax = 0.0 , |
||
double | _imin = 0.0 , |
||
double | _cmdMax = 0.0 , |
||
double | _cmdMin = 0.0 |
||
) |
Definition at line 59 of file RobotController.cpp.
void RobotController::update | ( | void | ) |
Definition at line 195 of file RobotController.cpp.
Definition at line 59 of file RobotController.h.
std::map<std::string, JointControllerPtr> gazebo::RobotController::joints [private] |
Definition at line 56 of file RobotController.h.
physics::ModelPtr gazebo::RobotController::modelPtr [private] |
Definition at line 55 of file RobotController.h.
common::Time gazebo::RobotController::prevUpdateTime [private] |
Definition at line 61 of file RobotController.h.