sr_tactile_sensor_controller.cpp
Go to the documentation of this file.
1 
12 // Copyright (C) 2012, hiDOF INC.
14 // Copyright (C) 2013, PAL Robotics S.L.
15 //
16 // Redistribution and use in source and binary forms, with or without
17 // modification, are permitted provided that the following conditions are met:
18 // * Redistributions of source code must retain the above copyright notice,
19 // this list of conditions and the following disclaimer.
20 // * Redistributions in binary form must reproduce the above copyright
21 // notice, this list of conditions and the following disclaimer in the
22 // documentation and/or other materials provided with the distribution.
23 // * Neither the name of PAL Robotics S.L. nor the names of its
24 // contributors may be used to endorse or promote products derived from
25 // this software without specific prior written permission.
26 //
27 // THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
28 // AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
29 // IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
30 // ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
31 // LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
32 // CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
33 // SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
34 // INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
35 // CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
36 // ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
37 // POSSIBILITY OF SUCH DAMAGE.
40 
46 #include <string>
47 
48 
49 namespace controller
50 {
52  : initialized_(false), sensors_(NULL)
53 {}
54 
55 bool SrTactileSensorController::init(ros_ethercat_model::RobotStateInterface* hw,
56  ros::NodeHandle &root_nh, ros::NodeHandle& controller_nh)
57 {
58  ROS_ASSERT(hw);
59 
60  ros_ethercat_model::RobotState* robot_state;
61  std::string robot_state_name;
62  controller_nh.param<std::string>("robot_state_name", robot_state_name, "unique_robot_hw");
63 
64  bool use_ns = true;
65  ros::NodeHandle nh_priv("~");
66 
67  try
68  {
69  robot_state = hw->getHandle(robot_state_name).getState();
70  }
72  {
73  ROS_ERROR_STREAM("Could not find robot state: " << robot_state_name << " Not loading the controller. " << e.what());
74  return false;
75  }
76 
77  if (!nh_priv.getParam("use_ns", use_ns))
78  {
79  ROS_INFO("Private parameter 'use_ns' not set, default is using namespace");
80  }
81 
82  if (!controller_nh.getParam("prefix", prefix_))
83  {
84  ROS_ERROR("Parameter 'prefix' not set");
85  return false;
86  }
87 
88  // this should handle the case where we don't want a prefix
89  if (!prefix_.empty())
90  {
91  if (use_ns)
93  else
94  nh_prefix_ = ros::NodeHandle(root_nh);
95 
96  prefix_+="_";
97  }
98  else
99  {
100  nh_prefix_ = ros::NodeHandle(root_nh);
101  }
102 
103  // get all sensors from the hardware interface
104  // apparently all the actuators have the tactile data copied in, so take the first one.
105  sr_actuator::SrMotorActuator* motor_actuator = static_cast<sr_actuator::SrMotorActuator*>(
106  robot_state->getActuator(prefix_+"FFJ0"));
107  if (motor_actuator)
108  {
109  sensors_ = motor_actuator->motor_state_.tactiles_;
110 
111  // get publishing period
112  if (!controller_nh.getParam("publish_rate", publish_rate_))
113  {
114  ROS_ERROR("Parameter 'publish_rate' not set");
115  return false;
116  }
117 
118  return true;
119  }
120  else
121  {
122  ROS_ERROR_STREAM("Could not find the " << prefix_ << "FFJ0 actuator");
123  return false;
124  }
125 }
126 
128 {
129  if (!initialized_)
130  {
131  if (sensors_)
132  {
133  if (!sensors_->empty())
134  {
135  if (!sensors_->at(0).type.empty())
136  {
137  if (sensors_->at(0).type == "pst")
138  {
140  }
141  else if (sensors_->at(0).type == "biotac")
142  {
144  }
145  else if (sensors_->at(0).type == "ubi")
146  {
148  }
149  else
150  {
151  ROS_FATAL_STREAM("Unknown tactile sensor type: " << sensors_->at(0).type);
152  }
153 
154  // initialize pusblisher and starting time
155  sensor_publisher_->init(time);
156  initialized_ = true;
157  }
158  }
159  }
160  }
161  else
162  {
163  sensor_publisher_->update(time, period);
164  }
165 }
166 
168 {
169 }
170 
172 {
173  // remove initialized flag to permit data type change and time resetting
174  initialized_ = false;
175 }
176 } // namespace controller
177 
178 
180 
181 /* For the emacs weenies in the crowd.
182 Local Variables:
183  c-basic-offset: 2
184 End:
185 */
virtual void stopping(const ros::Time &time)
virtual void starting(const ros::Time &time)
boost::shared_ptr< SrTactileSensorPublisher > sensor_publisher_
Publishes Biotac tactile state.
virtual void update(const ros::Time &time, const ros::Duration &period)
#define ROS_FATAL_STREAM(args)
std::vector< tactiles::AllTactileData > * sensors_
#define ROS_INFO(...)
bool param(const std::string &param_name, T &param_val, const T &default_val) const
virtual bool init(ros_ethercat_model::RobotStateInterface *hw, ros::NodeHandle &root_nh, ros::NodeHandle &controller_nh)
bool getParam(const std::string &key, std::string &s) const
#define ROS_ERROR_STREAM(args)
#define ROS_ASSERT(cond)
#define PLUGINLIB_EXPORT_CLASS(class_type, base_class_type)
derived from ImuSensorController author: Adolfo Rodriguez Tsouroukdissian
#define ROS_ERROR(...)
Publishes PST tactile state.


sr_tactile_sensor_controller
Author(s): Guillaume Walck
autogenerated on Tue Oct 13 2020 04:02:07