Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032
00033
00034
00035
00036
00037 #include <pluginlib/class_list_macros.h>
00038 #include <robot_controllers/scaled_mimic.h>
00039
00040 PLUGINLIB_EXPORT_CLASS(robot_controllers::ScaledMimicController, robot_controllers::Controller)
00041
00042 namespace robot_controllers
00043 {
00044
00045 int ScaledMimicController::init(ros::NodeHandle& nh, ControllerManager* manager)
00046 {
00047
00048 if (!manager)
00049 {
00050 initialized_ = false;
00051 return -1;
00052 }
00053
00054 Controller::init(nh, manager);
00055
00056
00057 std::string mimic, controlled;
00058 nh.param<std::string>("mimic_joint", mimic, "torso_lift_joint");
00059 nh.param<std::string>("controlled_joint", controlled, "bellows_joint");
00060 joint_to_mimic_ = manager->getJointHandle(mimic);
00061 joint_to_control_ = manager->getJointHandle(controlled);
00062 nh.param<double>("mimic_scale", scale_, 1.0);
00063
00064 initialized_ = true;
00065
00066
00067 bool autostart;
00068 nh.param("autostart", autostart, false);
00069 if (autostart)
00070 manager->requestStart(getName());
00071
00072 return 0;
00073 }
00074
00075 bool ScaledMimicController::start()
00076 {
00077 if (!initialized_)
00078 {
00079 ROS_ERROR_NAMED("ScaledMimicController",
00080 "Unable to start, not initialized.");
00081 return false;
00082 }
00083 return true;
00084 }
00085
00086 bool ScaledMimicController::stop(bool force)
00087 {
00088
00089 return true;
00090 }
00091
00092 bool ScaledMimicController::reset()
00093 {
00094
00095 return true;
00096 }
00097
00098 void ScaledMimicController::update(const ros::Time& now, const ros::Duration& dt)
00099 {
00100 if (!initialized_)
00101 return;
00102
00103 joint_to_control_->setPosition(scale_*joint_to_mimic_->getPosition(), 0, 0);
00104 }
00105
00106 std::vector<std::string> ScaledMimicController::getCommandedNames()
00107 {
00108 std::vector<std::string> names;
00109 names.push_back(joint_to_control_->getName());
00110 return names;
00111 }
00112
00113 std::vector<std::string> ScaledMimicController::getClaimedNames()
00114 {
00115
00116 return getCommandedNames();
00117 }
00118
00119 }