speed_scaling_state_controller.cpp
Go to the documentation of this file.
1 // this is for emacs file handling -*- mode: c++; indent-tabs-mode: nil -*-
2 
3 // -- BEGIN LICENSE BLOCK ----------------------------------------------
4 // Copyright 2019 FZI Forschungszentrum Informatik
5 //
6 // Licensed under the Apache License, Version 2.0 (the "License");
7 // you may not use this file except in compliance with the License.
8 // You may obtain a copy of the License at
9 //
10 // http://www.apache.org/licenses/LICENSE-2.0
11 //
12 // Unless required by applicable law or agreed to in writing, software
13 // distributed under the License is distributed on an "AS IS" BASIS,
14 // WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
15 // See the License for the specific language governing permissions and
16 // limitations under the License.
17 // -- END LICENSE BLOCK ------------------------------------------------
18 
19 //----------------------------------------------------------------------
26 //----------------------------------------------------------------------
27 
29 
31 
32 namespace ur_controllers
33 {
35  ros::NodeHandle& controller_nh)
36 {
37  // get all joint states from the hardware interface
38  const std::vector<std::string>& sensor_names = hw->getNames();
39  for (unsigned i = 0; i < sensor_names.size(); i++)
40  ROS_DEBUG("Got sensor %s", sensor_names[i].c_str());
41 
42  // get publishing period
43  if (!controller_nh.getParam("publish_rate", publish_rate_))
44  {
45  ROS_ERROR("Parameter 'publish_rate' not set");
46  return false;
47  }
48 
49  for (unsigned i = 0; i < sensor_names.size(); i++)
50  {
51  // sensor handle
52  sensors_.push_back(hw->getHandle(sensor_names[i]));
53 
54  // realtime publisher
55  RtPublisherPtr rt_pub(new realtime_tools::RealtimePublisher<std_msgs::Float64>(root_nh, sensor_names[i], 4));
56  realtime_pubs_.push_back(rt_pub);
57  }
58 
59  // Last published times
60  last_publish_times_.resize(sensor_names.size());
61  return true;
62 }
63 
65 {
66  // initialize time
67  for (unsigned i = 0; i < last_publish_times_.size(); i++)
68  {
69  last_publish_times_[i] = time;
70  }
71 }
72 
73 void SpeedScalingStateController::update(const ros::Time& time, const ros::Duration& /*period*/)
74 {
75  // limit rate of publishing
76  for (unsigned i = 0; i < realtime_pubs_.size(); i++)
77  {
78  if (publish_rate_ > 0.0 && last_publish_times_[i] + ros::Duration(1.0 / publish_rate_) < time)
79  {
80  // try to publish
81  if (realtime_pubs_[i]->trylock())
82  {
83  // we're actually publishing, so increment time
85 
86  // populate message
87  // realtime_pubs_[i]->msg_.header.stamp = time;
88  realtime_pubs_[i]->msg_.data = *sensors_[i].getScalingFactor();
89 
90  realtime_pubs_[i]->unlockAndPublish();
91  }
92  }
93  }
94 }
95 
97 {
98 }
99 } // namespace ur_controllers
100 
virtual void update(const ros::Time &time, const ros::Duration &) override
virtual void stopping(const ros::Time &) override
virtual bool init(SpeedScalingInterface *hw, ros::NodeHandle &root_nh, ros::NodeHandle &controller_nh) override
std::vector< std::string > getNames() const
virtual void starting(const ros::Time &time) override
bool getParam(const std::string &key, std::string &s) const
ResourceHandle getHandle(const std::string &name)
std::shared_ptr< realtime_tools::RealtimePublisher< std_msgs::Float64 > > RtPublisherPtr
#define PLUGINLIB_EXPORT_CLASS(class_type, base_class_type)
#define ROS_ERROR(...)
Hardware interface to support reading the speed scaling factor.
#define ROS_DEBUG(...)


ur_controllers
Author(s):
autogenerated on Sun Aug 22 2021 02:38:05