force_torque_sensor_controller.cpp
Go to the documentation of this file.
1 // Copyright (C) 2012, hiDOF INC.
3 // Copyright (C) 2013, PAL Robotics S.L.
4 //
5 // Redistribution and use in source and binary forms, with or without
6 // modification, are permitted provided that the following conditions are met:
7 // * Redistributions of source code must retain the above copyright notice,
8 // this list of conditions and the following disclaimer.
9 // * Redistributions in binary form must reproduce the above copyright
10 // notice, this list of conditions and the following disclaimer in the
11 // documentation and/or other materials provided with the distribution.
12 // * Neither the name of PAL Robotics S.L. nor the names of its
13 // contributors may be used to endorse or promote products derived from
14 // this software without specific prior written permission.
15 //
16 // THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
17 // AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
18 // IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
19 // ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
20 // LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
21 // CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
22 // SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
23 // INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
24 // CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
25 // ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
26 // POSSIBILITY OF SUCH DAMAGE.
28 
30 
31 
33 
34 
35 
37 {
38 
40  {
41  // get all joint states from the hardware interface
42  const std::vector<std::string>& sensor_names = hw->getNames();
43  for (unsigned i=0; i<sensor_names.size(); i++)
44  ROS_DEBUG("Got sensor %s", sensor_names[i].c_str());
45 
46  // get publishing period
47  if (!controller_nh.getParam("publish_rate", publish_rate_)){
48  ROS_ERROR("Parameter 'publish_rate' not set");
49  return false;
50  }
51 
52  for (unsigned i=0; i<sensor_names.size(); i++){
53  // sensor handle
54  sensors_.push_back(hw->getHandle(sensor_names[i]));
55 
56  // realtime publisher
58  realtime_pubs_.push_back(rt_pub);
59  }
60 
61  // Last published times
62  last_publish_times_.resize(sensor_names.size());
63  return true;
64  }
65 
67  {
68  // initialize time
69  for (unsigned i=0; i<last_publish_times_.size(); i++){
70  last_publish_times_[i] = time;
71  }
72  }
73 
74  void ForceTorqueSensorController::update(const ros::Time& time, const ros::Duration& /*period*/)
75  {
76  // limit rate of publishing
77  for (unsigned i=0; i<realtime_pubs_.size(); i++){
78  if (publish_rate_ > 0.0 && last_publish_times_[i] + ros::Duration(1.0/publish_rate_) < time){
79  // try to publish
80  if (realtime_pubs_[i]->trylock()){
81  // we're actually publishing, so increment time
83 
84  // populate message
85  realtime_pubs_[i]->msg_.header.stamp = time;
86  realtime_pubs_[i]->msg_.header.frame_id = sensors_[i].getFrameId();
87 
88  realtime_pubs_[i]->msg_.wrench.force.x = sensors_[i].getForce()[0];
89  realtime_pubs_[i]->msg_.wrench.force.y = sensors_[i].getForce()[1];
90  realtime_pubs_[i]->msg_.wrench.force.z = sensors_[i].getForce()[2];
91  realtime_pubs_[i]->msg_.wrench.torque.x = sensors_[i].getTorque()[0];
92  realtime_pubs_[i]->msg_.wrench.torque.y = sensors_[i].getTorque()[1];
93  realtime_pubs_[i]->msg_.wrench.torque.z = sensors_[i].getTorque()[2];
94 
95  realtime_pubs_[i]->unlockAndPublish();
96  }
97  }
98  }
99  }
100 
102  {}
103 
104 }
105 
virtual void update(const ros::Time &time, const ros::Duration &)
virtual bool init(hardware_interface::ForceTorqueSensorInterface *hw, ros::NodeHandle &root_nh, ros::NodeHandle &controller_nh)
std::vector< hardware_interface::ForceTorqueSensorHandle > sensors_
ForceTorqueSensorHandle getHandle(const std::string &name)
bool getParam(const std::string &key, std::string &s) const
std::vector< std::string > getNames() const
#define PLUGINLIB_EXPORT_CLASS(class_type, base_class_type)
#define ROS_ERROR(...)
#define ROS_DEBUG(...)


force_torque_sensor_controller
Author(s): Adolfo Rodriguez Tsouroukdissian
autogenerated on Sat Apr 18 2020 03:58:09