diffbot.cpp
Go to the documentation of this file.
1 // Copyright (C) 2013, PAL Robotics S.L.
3 //
4 // Redistribution and use in source and binary forms, with or without
5 // modification, are permitted provided that the following conditions are met:
6 // * Redistributions of source code must retain the above copyright notice,
7 // this list of conditions and the following disclaimer.
8 // * Redistributions in binary form must reproduce the above copyright
9 // notice, this list of conditions and the following disclaimer in the
10 // documentation and/or other materials provided with the distribution.
11 // * Neither the name of PAL Robotics, Inc. nor the names of its
12 // contributors may be used to endorse or promote products derived from
13 // this software without specific prior written permission.
14 //
15 // THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
16 // AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
17 // IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
18 // ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
19 // LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
20 // CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
21 // SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
22 // INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
23 // CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
24 // ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
25 // POSSIBILITY OF SUCH DAMAGE.
27 
28 // NOTE: The contents of this file have been taken largely from the ros_control wiki tutorials
29 
30 #include "diffbot.h"
31 #include <chrono>
32 #include <thread>
33 #include <controller_manager/controller_manager.h>
34 #include <ros/ros.h>
35 #include <rosgraph_msgs/Clock.h>
36 
37 int main(int argc, char **argv)
38 {
39  ros::init(argc, argv, "diffbot");
40  ros::NodeHandle nh;
41 
42  // This should be set in launch files as well
43  nh.setParam("/use_sim_time", true);
44 
45  Diffbot<> robot;
46  ROS_WARN_STREAM("period: " << robot.getPeriod().toSec());
47  controller_manager::ControllerManager cm(&robot, nh);
48 
49  ros::Publisher clock_publisher = nh.advertise<rosgraph_msgs::Clock>("/clock", 1);
50 
52  spinner.start();
53 
54  std::chrono::system_clock::time_point begin = std::chrono::system_clock::now();
55  std::chrono::system_clock::time_point end = std::chrono::system_clock::now();
56 
57  ros::Time internal_time(0);
58  const ros::Duration dt = robot.getPeriod();
59  double elapsed_secs = 0;
60 
61  while(ros::ok())
62  {
63  begin = std::chrono::system_clock::now();
64 
65  robot.read();
66  cm.update(internal_time, dt);
67 
68  robot.write();
69 
70  end = std::chrono::system_clock::now();
71 
72  elapsed_secs = std::chrono::duration_cast<std::chrono::duration<double> >((end - begin)).count();
73 
74  if (dt.toSec() - elapsed_secs < 0.0)
75  {
77  0.1, "Control cycle is taking to much time, elapsed: " << elapsed_secs);
78  }
79  else
80  {
81  ROS_DEBUG_STREAM_THROTTLE(1.0, "Control cycle is, elapsed: " << elapsed_secs);
82  std::this_thread::sleep_for(std::chrono::duration<double>(dt.toSec() - elapsed_secs));
83  }
84 
85  rosgraph_msgs::Clock clock;
86  clock.clock = ros::Time(internal_time);
87  clock_publisher.publish(clock);
88  internal_time += dt;
89  }
90  spinner.stop();
91 
92  return 0;
93 }
ros::NodeHandle::setParam
void setParam(const std::string &key, bool b) const
ros::Publisher
ros::init
ROSCPP_DECL void init(const M_string &remappings, const std::string &name, uint32_t options=0)
ros.h
ros::AsyncSpinner
diffbot.h
ros::Publisher::publish
void publish(const boost::shared_ptr< M > &message) const
ros::NodeHandle::advertise
Publisher advertise(AdvertiseOptions &ops)
ros::ok
ROSCPP_DECL bool ok()
spinner
void spinner()
ROS_WARN_STREAM
#define ROS_WARN_STREAM(args)
ROS_WARN_STREAM_THROTTLE
#define ROS_WARN_STREAM_THROTTLE(period, args)
main
int main(int argc, char **argv)
Definition: diffbot.cpp:37
Diffbot::write
void write()
Definition: diffbot.h:106
Diffbot::read
void read()
Definition: diffbot.h:85
Diffbot
Definition: diffbot.h:51
ROS_DEBUG_STREAM_THROTTLE
#define ROS_DEBUG_STREAM_THROTTLE(period, args)
Diffbot::getPeriod
ros::Duration getPeriod() const
Definition: diffbot.h:83
ros::Time
DurationBase< Duration >::toSec
double toSec() const
ros::Duration
ros::NodeHandle


diff_drive_controller
Author(s): Bence Magyar
autogenerated on Fri May 24 2024 02:41:05