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>
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.
robot_controllers::ScaledMimicController::ScaledMimicController |
( |
| ) |
|
|
inline |
virtual robot_controllers::ScaledMimicController::~ScaledMimicController |
( |
| ) |
|
|
inlinevirtual |
std::vector< std::string > robot_controllers::ScaledMimicController::getClaimedNames |
( |
| ) |
|
|
virtual |
std::vector< std::string > robot_controllers::ScaledMimicController::getCommandedNames |
( |
| ) |
|
|
virtual |
virtual std::string robot_controllers::ScaledMimicController::getType |
( |
| ) |
|
|
inlinevirtual |
Initialize the controller and any required data structures.
- Parameters
-
nh | Node handle for this controller. |
manager | The controller manager instance, this is needed for the controller to get information about joints, etc. |
- Returns
- 0 if succesfully configured, negative values are error codes.
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.
- Returns
- True if successfully reset, false otherwise.
Implements robot_controllers::Controller.
Definition at line 92 of file scaled_mimic.cpp.
bool robot_controllers::ScaledMimicController::start |
( |
| ) |
|
|
virtual |
bool robot_controllers::ScaledMimicController::stop |
( |
bool |
force | ) |
|
|
virtual |
Attempt to stop the controller. This should be called only by the ControllerManager instance.
- Parameters
-
force | Should we force the controller to stop? Some controllers may wish to continue running until they absolutely have to stop. |
- Returns
- True if successfully stopped, false otherwise.
Implements robot_controllers::Controller.
Definition at line 86 of file scaled_mimic.cpp.
bool robot_controllers::ScaledMimicController::initialized_ |
|
private |
JointHandlePtr robot_controllers::ScaledMimicController::joint_to_control_ |
|
private |
JointHandlePtr robot_controllers::ScaledMimicController::joint_to_mimic_ |
|
private |
double robot_controllers::ScaledMimicController::scale_ |
|
private |
The documentation for this class was generated from the following files: