four_wheel_steering.cpp
Go to the documentation of this file.
1 // NOTE: The contents of this file have been taken largely from the ros_control wiki tutorials
2 
3 #include "four_wheel_steering.h"
4 #include <chrono>
5 #include <thread>
6 #include <controller_manager/controller_manager.h>
7 #include <ros/ros.h>
8 #include <rosgraph_msgs/Clock.h>
9 
10 int main(int argc, char **argv)
11 {
12  ros::init(argc, argv, "four_wheel_steering");
13  ros::NodeHandle nh;
14 
15  // This should be set in launch files as well
16  nh.setParam("/use_sim_time", true);
17 
18  FourWheelSteering robot;
19  ROS_WARN_STREAM("period: " << robot.getPeriod().toSec());
20  controller_manager::ControllerManager cm(&robot, nh);
21 
22  ros::Publisher clock_publisher = nh.advertise<rosgraph_msgs::Clock>("/clock", 1);
23 
25  spinner.start();
26 
27  std::chrono::system_clock::time_point begin = std::chrono::system_clock::now();
28  std::chrono::system_clock::time_point end = std::chrono::system_clock::now();
29 
30  ros::Time internal_time(0);
31  const ros::Duration dt = robot.getPeriod();
32  double elapsed_secs = 0;
33 
34  while(ros::ok())
35  {
36  begin = std::chrono::system_clock::now();
37 
38  robot.read();
39  cm.update(internal_time, dt);
40  robot.write();
41 
42  end = std::chrono::system_clock::now();
43 
44  elapsed_secs = std::chrono::duration_cast<std::chrono::duration<double> >((end - begin)).count();
45 
46  if (dt.toSec() - elapsed_secs < 0.0)
47  {
49  0.1, "Control cycle is taking to much time, elapsed: " << elapsed_secs);
50  }
51  else
52  {
53  ROS_DEBUG_STREAM_THROTTLE(1.0, "Control cycle is, elapsed: " << elapsed_secs);
54  std::this_thread::sleep_for(std::chrono::duration<double>(dt.toSec() - elapsed_secs));
55  }
56 
57  rosgraph_msgs::Clock clock;
58  clock.clock = ros::Time(internal_time);
59  clock_publisher.publish(clock);
60  internal_time += dt;
61  }
62  spinner.stop();
63 
64  return 0;
65 }
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
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)
ROS_DEBUG_STREAM_THROTTLE
#define ROS_DEBUG_STREAM_THROTTLE(period, args)
FourWheelSteering
Definition: four_wheel_steering.h:24
FourWheelSteering::getPeriod
ros::Duration getPeriod() const
Definition: four_wheel_steering.h:63
FourWheelSteering::write
void write()
Definition: four_wheel_steering.h:98
ros::Time
FourWheelSteering::read
void read()
Definition: four_wheel_steering.h:65
four_wheel_steering.h
DurationBase< Duration >::toSec
double toSec() const
main
int main(int argc, char **argv)
Definition: four_wheel_steering.cpp:10
ros::Duration
ros::NodeHandle


four_wheel_steering_controller
Author(s): Vincent Rousseau
autogenerated on Fri May 24 2024 02:41:15