srh_syntouch_controllers.cpp
Go to the documentation of this file.
1 /*
2 * Copyright 2011 Shadow Robot Company Ltd.
3 *
4 * This program is free software: you can redistribute it and/or modify it
5 * under the terms of the GNU General Public License as published by the Free
6 * Software Foundation version 2 of the License.
7 *
8 * This program is distributed in the hope that it will be useful, but WITHOUT
9 * ANY WARRANTY; without even the implied warranty of MERCHANTABILITY or
10 * FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License for
11 * more details.
12 *
13 * You should have received a copy of the GNU General Public License along
14 * with this program. If not, see <http://www.gnu.org/licenses/>.
15 */
16 
26 #include "../example/srh_syntouch_controllers.hpp"
27 #include "angles/angles.h"
29 #include <string>
30 #include <sstream>
31 #include <math.h>
33 #include <std_msgs/Float64.h>
34 
36 
37 namespace controller
38 {
39 
41  : SrController()
42  {
43  }
44 
46  {
48  }
49 
50  bool SrhSyntouchController::init(ros_ethercat_model::RobotStateInterface *robot, ros::NodeHandle &n)
51  {
52  ROS_ASSERT(robot);
53 
54  std::string robot_state_name;
55  node_.param<std::string>("robot_state_name", robot_state_name, "unique_robot_hw");
56 
57  try
58  {
59  robot_ = robot->getHandle(robot_state_name).getState();
60  }
62  {
63  ROS_ERROR_STREAM("Could not find robot state: " << robot_state_name << " Not loading the controller. " <<
64  e.what());
65  return false;
66  }
67 
68  node_ = n;
69 
70  if (!node_.getParam("joint", joint_name_))
71  {
72  ROS_ERROR("No joint given (namespace: %s)", node_.getNamespace().c_str());
73  return false;
74  }
75 
76  ROS_DEBUG(" --------- ");
77  ROS_DEBUG_STREAM("Init: " << joint_name_);
78 
79  joint_state_ = robot_->getJointState(joint_name_);
80  if (!joint_state_)
81  {
82  ROS_ERROR("SrhMixedPositionVelocityController could not find joint named \"%s\"\n",
83  joint_name_.c_str());
84  return false;
85  }
86 
87  // init the pointer to the biotacs data, updated at 1kHz
88  actuator_ = static_cast<sr_actuator::SrMotorActuator *>(robot_->getActuator(joint_name_));
89 
90  after_init();
91  return true;
92  }
93 
94 
96  {
97  command_ = joint_state_->position_;
98 
99  ROS_WARN_STREAM("Reseting PID for joint " << joint_state_->joint_->name);
100  }
101 
102  void SrhSyntouchController::update(const ros::Time &time, const ros::Duration &period)
103  {
105  ROS_ASSERT(joint_state_->joint_);
106 
107  if (initialized_)
108  {
109  command_ = joint_state_->commanded_position_;
110  }
111  else
112  {
113  initialized_ = true;
114  command_ = joint_state_->position_;
115  }
116 
118  // POSITION
119 
120  // Compute position error:
121  double error_position = command_ - joint_state_->position_;
122 
124  // TACTILES
125 
126  // you have access here to the whole data coming from the 5 tactiles at full speed.
127  double my_first_finger_tactile_pac = actuator_->motor_state_.tactiles_->at(0).biotac.get_pac().back();
128  if (loop_count_ % 10 == 0)
129  {
130  ROS_ERROR_STREAM("PAC, tactile " << my_first_finger_tactile_pac);
131  }
132 
134  // EFFORT
135 
136  // Compute the commanded effort to send to the motor
137  double commanded_effort = 0.0;
138  // @todo compute the force demand by combining the information you
139  // want. You can have a look at the mixed controller to see a
140  // working implementation of a controller using different pid loops.
141 
142  joint_state_->commanded_effort_ = commanded_effort;
143 
144  if (loop_count_ % 10 == 0)
145  {
147  {
148  controller_state_publisher_->msg_.header.stamp = time;
149  controller_state_publisher_->msg_.set_point = command_;
150 
151  controller_state_publisher_->msg_.process_value = joint_state_->position_;
152  controller_state_publisher_->msg_.process_value_dot = joint_state_->velocity_;
153 
154  controller_state_publisher_->msg_.error = error_position;
155  controller_state_publisher_->msg_.time_step = period.toSec();
156 
157  controller_state_publisher_->msg_.command = commanded_effort;
158  controller_state_publisher_->msg_.measured_effort = joint_state_->effort_;
159 
160  controller_state_publisher_->unlockAndPublish();
161  }
162  }
163  loop_count_++;
164  }
165 } // namespace controller
166 
167 /* For the emacs weenies in the crowd.
168 Local Variables:
169  c-basic-offset: 2
170 End:
171 */
172 
173 
ros_ethercat_model::JointState * joint_state_
boost::scoped_ptr< realtime_tools::RealtimePublisher< sr_robot_msgs::JointControllerState > > controller_state_publisher_
virtual void update(const ros::Time &time, const ros::Duration &period)
Issues commands to the joint. Should be called at regular intervals.
#define ROS_ERROR(...)
#define ROS_DEBUG(...)
ros::Subscriber sub_command_
ros_ethercat_model::RobotState * robot_
PLUGINLIB_EXPORT_CLASS(cached_ik_kinematics_plugin::CachedIKKinematicsPlugin< kdl_kinematics_plugin::KDLKinematicsPlugin >, kinematics::KinematicsBase)
bool param(const std::string &param_name, T &param_val, const T &default_val) const
sr_actuator::SrMotorActuator * actuator_
const char * what() const noexcept override
bool init(ros_ethercat_model::RobotStateInterface *robot, ros::NodeHandle &n)
bool getParam(const std::string &key, std::string &s) const
virtual void starting(const ros::Time &time)
#define ROS_WARN_STREAM(args)
#define ROS_DEBUG_STREAM(args)
std::vector< tactiles::AllTactileData > * tactiles_
const std::string & getNamespace() const
#define ROS_ERROR_STREAM(args)
#define ROS_ASSERT(cond)
SrMotorActuatorState motor_state_
void after_init()
call this function at the end of the init function in the inheriting classes.


sr_mechanism_controllers
Author(s): Ugo Cupcic
autogenerated on Mon Feb 28 2022 23:52:31