control_node.cpp
Go to the documentation of this file.
1 // -- BEGIN LICENSE BLOCK ----------------------------------------------
2 // Copyright 2020 FZI Forschungszentrum Informatik
3 // Created on behalf of Universal Robots A/S
4 //
5 // Licensed under the Apache License, Version 2.0 (the "License");
6 // you may not use this file except in compliance with the License.
7 // You may obtain a copy of the License at
8 //
9 // http://www.apache.org/licenses/LICENSE-2.0
10 //
11 // Unless required by applicable law or agreed to in writing, software
12 // distributed under the License is distributed on an "AS IS" BASIS,
13 // WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
14 // See the License for the specific language governing permissions and
15 // limitations under the License.
16 // -- END LICENSE BLOCK ------------------------------------------------
17 
18 //-----------------------------------------------------------------------------
25 //-----------------------------------------------------------------------------
26 
27 // Ros
28 #include <ros/ros.h>
29 
30 // Ros control
32 
33 // This project
34 #include "hw_interface.h"
35 #include "ros/time.h"
36 
37 int main(int argc, char** argv)
38 {
39  ros::init(argc, argv, "hw_interface_example");
40  ros::NodeHandle nh;
41  examples::HWInterface hw_interface;
43 
44  int control_rate;
45  if (!nh.getParam("control_rate", control_rate))
46  {
47  control_rate = 125;
48  ROS_INFO_STREAM("Failed to load 'control_rate' from parameter server. Using default " << control_rate);
49  }
50 
51  // Control cycle for the robot
52  ros::Rate rate(control_rate);
53 
55  spinner.start();
56 
57  while (ros::ok())
58  {
59  auto period = rate.expectedCycleTime(); // use nominal cycle
60 
61  hw_interface.read(ros::Time::now(), period);
62  hw_interface.write(ros::Time::now(), period);
63  controller_manager.update(ros::Time::now(), period);
64 
65  rate.sleep();
66  }
67 
68  return 0;
69 }
controller_manager::ControllerManager
main
int main(int argc, char **argv)
Definition: control_node.cpp:37
ros::Rate::expectedCycleTime
Duration expectedCycleTime() const
controller_manager
ros::init
ROSCPP_DECL void init(const M_string &remappings, const std::string &name, uint32_t options=0)
ros::NodeHandle::getParam
bool getParam(const std::string &key, bool &b) const
ros.h
time.h
examples::HWInterface::read
void read(const ros::Time &time, const ros::Duration &period) override
Definition: hw_interface.cpp:159
ros::AsyncSpinner
examples::HWInterface
Definition: hw_interface.h:70
controller_manager.h
ros::ok
ROSCPP_DECL bool ok()
spinner
void spinner()
hw_interface.h
examples::HWInterface::write
void write(const ros::Time &time, const ros::Duration &period) override
Definition: hw_interface.cpp:164
ROS_INFO_STREAM
#define ROS_INFO_STREAM(args)
ros::Rate::sleep
bool sleep()
ros::Rate
ros::NodeHandle
ros::Time::now
static Time now()


pass_through_controllers
Author(s):
autogenerated on Tue Oct 15 2024 02:10:52