srh_example_controller.cpp
Go to the documentation of this file.
00001 
00027 #include "../example/srh_example_controller.hpp"
00028 #include <angles/angles.h>
00029 #include <pluginlib/class_list_macros.h>
00030 
00031 #include <std_msgs/Float64.h>
00032 
00033 //Register the controller to be able to load it with the controller manager.
00034 PLUGINLIB_EXPORT_CLASS( controller::SrhExampleController, controller_interface::ControllerBase)
00035 
00036 using namespace std;
00037 
00038 namespace controller {
00039 
00040   SrhExampleController::SrhExampleController()
00041     : SrController()
00042   {
00043     //This constructor is kept empty: the init functions
00044     // are called by the controller manager when the controllers are started.
00045   }
00046 
00047   SrhExampleController::~SrhExampleController()
00048   {
00049     //Stop subscribing to the command topic.
00050     sub_command_.shutdown();
00051   }
00052 
00053   bool SrhExampleController::init(ros_ethercat_model::RobotState *robot, ros::NodeHandle &n)
00054   {
00055     assert(robot);
00056     node_ = n;
00057 
00058     //read the joint we're controlling from the parameter server.
00059     std::string joint_name;
00060     if (!node_.getParam("joint", joint_name)) {
00061       ROS_ERROR("No joint given (namespace: %s)", node_.getNamespace().c_str());
00062       return false;
00063     }
00064 
00065     //set the state publisher for this controller:
00066     // This publisher publishes interesting data for the current controller.
00067     // (useful for debugging / tuning)
00068     // Feel free to create a different message type, to publish more meaningful
00069     // information for your controller (cf srh_mixed_position_velocity_controller.cpp)
00070     controller_state_publisher_.reset(
00071       new realtime_tools::RealtimePublisher<control_msgs::JointControllerState>
00072       (node_, "state", 1));
00073 
00074     //Calls the 2nd init function to finish initializing
00075     return init(robot, joint_name);
00076   }
00077 
00078   bool SrhExampleController::init(ros_ethercat_model::RobotState *robot, const std::string &joint_name)
00079   {
00080     assert(robot);
00081     robot_ = robot;
00082 
00083     //We need to store 2 different joint states for the joint 0s:
00084     // They control the distal and the middle joint with the same control.
00085     if( joint_name.substr(3,1).compare("0") == 0)
00086     {
00087       has_j2 = true;
00088 
00089       //The joint 0 is name *FJ0, and is controlling *J1 + *J2.
00090       std::string j1 = joint_name.substr(0,3) + "1";
00091       std::string j2 = joint_name.substr(0,3) + "2";
00092 
00093       //Get the pointer to the joint state for *J1
00094       joint_state_ = robot_->getJointState(j1);
00095       if (!joint_state_)
00096       {
00097         ROS_ERROR("SrhMixedPositionVelocityController could not find joint named \"%s\"\n",
00098                   joint_name.c_str());
00099         return false;
00100       }
00101 
00102       //Get the pointer to the joint state for *J2
00103       joint_state_2 = robot_->getJointState(j2);
00104       if (!joint_state_2)
00105       {
00106         ROS_ERROR("SrhMixedPositionVelocityController could not find joint named \"%s\"\n",
00107                   joint_name.c_str());
00108         return false;
00109       }
00110     }
00111     else //"normal" joints: one controller controls one joint
00112     {
00113       has_j2 = false;
00114 
00115       //get the pointer to the joint state
00116       joint_state_ = robot_->getJointState(joint_name);
00117       if (!joint_state_)
00118       {
00119         ROS_ERROR("SrhMixedPositionVelocityController could not find joint named \"%s\"\n",
00120                   joint_name.c_str());
00121         return false;
00122       }
00123     }
00124 
00125     // after init creates the subscriber to the /command topic
00126     after_init();
00127     return true;
00128   }
00129 
00130 
00131   void SrhExampleController::starting(const ros::Time& time)
00132   {
00133     //Here we set the command to be = to the current position
00134     if( has_j2 ) //if it's *J0, then pos = *J1->pos + *J2->pos
00135       command_ = joint_state_->position_ + joint_state_2->position_;
00136     else
00137       command_ = joint_state_->position_;
00138   }
00139 
00140   void SrhExampleController::update(const ros::Time& time, const ros::Duration& period)
00141   {
00142     assert(robot_ != NULL);
00143     assert(joint_state_->joint_);
00144 
00145     //make sure the controller has been initialised,
00146     // to avoid sending a crazy command.
00147     if (!initialized_)
00148     {
00149       starting(time);
00150 
00151       initialized_ = true;
00152     }
00153 
00154     //compute the commanded effort you want to send
00155     // to the motor: you can use whatever algorithm
00156     // you want. To see more complex examples on how
00157     // to use a pid loop / more than one loop, just
00158     // go to the src directory, and have a look at
00159     // srh_mixed_position_velocity_controller.cpp
00160 
00161     //we start by computing the position error
00162     double error_position = 0.0;
00163     if( has_j2 )
00164     {
00165       //For *J0, the position error is equal to the command - (*J1 + *J2)
00166       error_position = command_ - (joint_state_->position_ + joint_state_2->position_);
00167     }
00168     else
00169       error_position = command_ - joint_state_->position_;
00170 
00171     //Here I'm simply doing a dummy P controller, with a fixed gain.
00172     // It can't be used in the real life obviously. That's where you
00173     // should WRITE YOUR ALGORITHM
00174     double commanded_effort = 10* error_position;
00175 
00176     //Update the commanded effort.
00177     if( has_j2 ) //The motor in *J0 is attached to the *J2
00178       joint_state_2->commanded_effort_ = commanded_effort;
00179     else
00180       joint_state_->commanded_effort_ = commanded_effort;
00181 
00182     if(loop_count_ % 10 == 0) //publishes the joint state at 100Hz
00183     {
00184       if(controller_state_publisher_ && controller_state_publisher_->trylock())
00185       {
00186         controller_state_publisher_->msg_.header.stamp = time;
00187         controller_state_publisher_->msg_.set_point = command_;
00188 
00189         if( has_j2 )
00190         {
00191           controller_state_publisher_->msg_.process_value = joint_state_->position_ + joint_state_2->position_;
00192           controller_state_publisher_->msg_.process_value_dot = joint_state_->velocity_ + joint_state_2->velocity_;
00193         }
00194         else
00195         {
00196           controller_state_publisher_->msg_.process_value = joint_state_->position_;
00197           controller_state_publisher_->msg_.process_value_dot = joint_state_->velocity_;
00198         }
00199 
00200         controller_state_publisher_->msg_.error = error_position;
00201         controller_state_publisher_->msg_.time_step = period.toSec();
00202         controller_state_publisher_->msg_.command = commanded_effort;
00203 
00204         controller_state_publisher_->unlockAndPublish();
00205       }
00206     }
00207     loop_count_++;
00208   }
00209 }
00210 
00211 /* For the emacs weenies in the crowd.
00212 Local Variables:
00213    c-basic-offset: 2
00214 End:
00215 */
00216 
00217 


sr_mechanism_controllers
Author(s): Ugo Cupcic
autogenerated on Fri Aug 21 2015 12:26:14