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 
35 
36 
38 {
39 
41  {
42  // get all joint states from the hardware interface
43  const std::vector<std::string>& sensor_names = hw->getNames();
44  for (unsigned i=0; i<sensor_names.size(); i++)
45  ROS_DEBUG("Got sensor %s", sensor_names[i].c_str());
46 
47  // get publishing period
48  if (!controller_nh.getParam("publish_rate", publish_rate_)){
49  ROS_ERROR("Parameter 'publish_rate' not set");
50  return false;
51  }
52 
53  for (unsigned i=0; i<sensor_names.size(); i++){
54  // sensor handle
55  sensors_.push_back(hw->getHandle(sensor_names[i]));
56 
57  // realtime publisher
59  realtime_pubs_.push_back(rt_pub);
60  }
61 
62  // Last published times
63  last_publish_times_.resize(sensor_names.size());
64  return true;
65  }
66 
68  {
69  // initialize time
70  for (unsigned i=0; i<last_publish_times_.size(); i++){
71  last_publish_times_[i] = time;
72  }
73  }
74 
75  void ForceTorqueSensorController::update(const ros::Time& time, const ros::Duration& /*period*/)
76  {
77  // limit rate of publishing
78  for (unsigned i=0; i<realtime_pubs_.size(); i++){
79  if (publish_rate_ > 0.0 && last_publish_times_[i] + ros::Duration(1.0/publish_rate_) < time){
80  // try to publish
81  if (realtime_pubs_[i]->trylock()){
82  // we're actually publishing, so increment time
84 
85  // populate message
86  realtime_pubs_[i]->msg_.header.stamp = time;
87  realtime_pubs_[i]->msg_.header.frame_id = sensors_[i].getFrameId();
88 
89  realtime_pubs_[i]->msg_.wrench.force.x = sensors_[i].getForce()[0];
90  realtime_pubs_[i]->msg_.wrench.force.y = sensors_[i].getForce()[1];
91  realtime_pubs_[i]->msg_.wrench.force.z = sensors_[i].getForce()[2];
92  realtime_pubs_[i]->msg_.wrench.torque.x = sensors_[i].getTorque()[0];
93  realtime_pubs_[i]->msg_.wrench.torque.y = sensors_[i].getTorque()[1];
94  realtime_pubs_[i]->msg_.wrench.torque.z = sensors_[i].getTorque()[2];
95 
96  realtime_pubs_[i]->unlockAndPublish();
97  }
98  }
99  }
100  }
101 
103  {}
104 
105 }
106 
force_torque_sensor_controller::ForceTorqueSensorController::stopping
virtual void stopping(const ros::Time &)
Definition: force_torque_sensor_controller.cpp:102
ResourceManager< ForceTorqueSensorHandle >::getNames
std::vector< std::string > getNames() const
force_torque_sensor_controller::ForceTorqueSensorController
Definition: force_torque_sensor_controller.h:44
HardwareResourceManager< ForceTorqueSensorHandle >::getHandle
ForceTorqueSensorHandle getHandle(const std::string &name)
force_torque_sensor_controller.h
ros::NodeHandle::getParam
bool getParam(const std::string &key, bool &b) const
force_torque_sensor_controller::ForceTorqueSensorController::last_publish_times_
std::vector< ros::Time > last_publish_times_
Definition: force_torque_sensor_controller.h:58
force_torque_sensor_controller::ForceTorqueSensorController::publish_rate_
double publish_rate_
Definition: force_torque_sensor_controller.h:59
force_torque_sensor_controller::ForceTorqueSensorController::starting
virtual void starting(const ros::Time &time)
Definition: force_torque_sensor_controller.cpp:67
force_torque_sensor_controller::ForceTorqueSensorController::RtPublisherPtr
std::shared_ptr< realtime_tools::RealtimePublisher< geometry_msgs::WrenchStamped > > RtPublisherPtr
Definition: force_torque_sensor_controller.h:56
realtime_tools::RealtimePublisher
controller_interface::ControllerBase
PLUGINLIB_EXPORT_CLASS
#define PLUGINLIB_EXPORT_CLASS(class_type, base_class_type)
ROS_DEBUG
#define ROS_DEBUG(...)
hardware_interface::ForceTorqueSensorInterface
force_torque_sensor_controller::ForceTorqueSensorController::update
virtual void update(const ros::Time &time, const ros::Duration &)
Definition: force_torque_sensor_controller.cpp:75
force_torque_sensor_controller::ForceTorqueSensorController::realtime_pubs_
std::vector< RtPublisherPtr > realtime_pubs_
Definition: force_torque_sensor_controller.h:57
force_torque_sensor_controller::ForceTorqueSensorController::init
virtual bool init(hardware_interface::ForceTorqueSensorInterface *hw, ros::NodeHandle &root_nh, ros::NodeHandle &controller_nh)
Definition: force_torque_sensor_controller.cpp:40
ros::Time
ROS_ERROR
#define ROS_ERROR(...)
class_list_macros.hpp
force_torque_sensor_controller::ForceTorqueSensorController::sensors_
std::vector< hardware_interface::ForceTorqueSensorHandle > sensors_
Definition: force_torque_sensor_controller.h:55
force_torque_sensor_controller
Definition: force_torque_sensor_controller.h:40
ros::Duration
ros::NodeHandle


force_torque_sensor_controller
Author(s): Adolfo Rodriguez Tsouroukdissian
autogenerated on Fri May 24 2024 02:41:11