Controller for a having one joint be a (scaled) mimic of another. Primary design use case is making a fake bellows joint that moves in relation to a torso lift joint. More...
#include <scaled_mimic.h>
Public Member Functions | |
virtual std::vector< std::string > | getClaimedNames () |
Get the names of joints/controllers which this controller exclusively claims. | |
virtual std::vector< std::string > | getCommandedNames () |
Get the names of joints/controllers which this controller commands. | |
virtual std::string | getType () |
Get the type of this controller. | |
virtual int | init (ros::NodeHandle &nh, ControllerManager *manager) |
Initialize the controller and any required data structures. | |
virtual bool | reset () |
Cleanly reset the controller to it's initial state. Some controllers may choose to stop themselves. This is mainly used in the case of the the robot exiting some fault condition. | |
ScaledMimicController () | |
virtual bool | start () |
Attempt to start the controller. This should be called only by the ControllerManager instance. | |
virtual bool | stop (bool force) |
Attempt to stop the controller. This should be called only by the ControllerManager instance. | |
virtual void | update (const ros::Time &now, const ros::Duration &dt) |
This is the update loop for the controller. | |
virtual | ~ScaledMimicController () |
Private Types | |
typedef actionlib::SimpleActionServer < control_msgs::GripperCommandAction > | server_t |
Private Attributes | |
bool | initialized_ |
JointHandlePtr | joint_to_control_ |
JointHandlePtr | joint_to_mimic_ |
double | scale_ |
Controller for a having one joint be a (scaled) mimic of another. Primary design use case is making a fake bellows joint that moves in relation to a torso lift joint.
Definition at line 58 of file scaled_mimic.h.
typedef actionlib::SimpleActionServer<control_msgs::GripperCommandAction> robot_controllers::ScaledMimicController::server_t [private] |
Definition at line 60 of file scaled_mimic.h.
Definition at line 63 of file scaled_mimic.h.
virtual robot_controllers::ScaledMimicController::~ScaledMimicController | ( | ) | [inline, virtual] |
Definition at line 64 of file scaled_mimic.h.
std::vector< std::string > robot_controllers::ScaledMimicController::getClaimedNames | ( | ) | [virtual] |
Get the names of joints/controllers which this controller exclusively claims.
Implements robot_controllers::Controller.
Definition at line 113 of file scaled_mimic.cpp.
std::vector< std::string > robot_controllers::ScaledMimicController::getCommandedNames | ( | ) | [virtual] |
Get the names of joints/controllers which this controller commands.
Implements robot_controllers::Controller.
Definition at line 106 of file scaled_mimic.cpp.
virtual std::string robot_controllers::ScaledMimicController::getType | ( | ) | [inline, virtual] |
Get the type of this controller.
Reimplemented from robot_controllers::Controller.
Definition at line 107 of file scaled_mimic.h.
int robot_controllers::ScaledMimicController::init | ( | ros::NodeHandle & | nh, |
ControllerManager * | manager | ||
) | [virtual] |
Initialize the controller and any required data structures.
nh | Node handle for this controller. |
manager | The controller manager instance, this is needed for the controller to get information about joints, etc. |
Reimplemented from robot_controllers::Controller.
Definition at line 45 of file scaled_mimic.cpp.
bool robot_controllers::ScaledMimicController::reset | ( | ) | [virtual] |
Cleanly reset the controller to it's initial state. Some controllers may choose to stop themselves. This is mainly used in the case of the the robot exiting some fault condition.
Implements robot_controllers::Controller.
Definition at line 92 of file scaled_mimic.cpp.
bool robot_controllers::ScaledMimicController::start | ( | ) | [virtual] |
Attempt to start the controller. This should be called only by the ControllerManager instance.
Implements robot_controllers::Controller.
Definition at line 75 of file scaled_mimic.cpp.
bool robot_controllers::ScaledMimicController::stop | ( | bool | force | ) | [virtual] |
Attempt to stop the controller. This should be called only by the ControllerManager instance.
force | Should we force the controller to stop? Some controllers may wish to continue running until they absolutely have to stop. |
Implements robot_controllers::Controller.
Definition at line 86 of file scaled_mimic.cpp.
void robot_controllers::ScaledMimicController::update | ( | const ros::Time & | now, |
const ros::Duration & | dt | ||
) | [virtual] |
This is the update loop for the controller.
time | The system time. |
dt | The timestep since last call to update. |
Implements robot_controllers::Controller.
Definition at line 98 of file scaled_mimic.cpp.
bool robot_controllers::ScaledMimicController::initialized_ [private] |
Definition at line 119 of file scaled_mimic.h.
Definition at line 121 of file scaled_mimic.h.
Definition at line 120 of file scaled_mimic.h.
double robot_controllers::ScaledMimicController::scale_ [private] |
Definition at line 122 of file scaled_mimic.h.