diffbot_base.cpp
Go to the documentation of this file.
1 #include <ros/ros.h>
4 
5 int main(int argc, char **argv)
6 {
7  // Initialize the ROS node
8  ros::init(argc, argv, "diffbot_hw_interface");
10 
11  // Create an instance of your robot so that this instance knows about all
12  // the resources that are available.
14 
15  // Create an instance of the controller manager and pass it the robot,
16  // so that it can handle its resources.
18 
19  // Setup a separate thread that will be used to service ROS callbacks.
20  // NOTE: We run the ROS loop in a separate thread as external calls such
21  // as service callbacks to load controllers can block the (main) control loop
23  spinner.start();
24 
25  // Setup for the control loop.
26  ros::Time prev_time = ros::Time::now();
27  ros::Rate rate(10.0); // 50 Hz rate
28  rate.sleep();
29 
30  // Blocks until shutdown signal recieved
31  while (ros::ok())
32  {
33  // Basic bookkeeping to get the system time in order to compute the control period.
34  const ros::Time time = ros::Time::now();
35  const ros::Duration period = time - prev_time;
36  prev_time = time;
37 
38  // Execution of the actual control loop.
39  diffBot.read(time, period);
40  // If needed, its possible to define transmissions in software by calling the
41  // transmission_interface::ActuatorToJointPositionInterface::propagate()
42  // after reading the joint states.
43  cm.update(time, period);
44  // In case of software transmissions, use
45  // transmission_interface::JointToActuatorEffortHandle::propagate()
46  // to convert from the joint space to the actuator space.
47  diffBot.write(time, period);
48 
49  // All these steps keep getting repeated with the specified rate.
50  rate.sleep();
51  }
52  return 0;
53 }
controller_manager::ControllerManager
ros::init
ROSCPP_DECL void init(const M_string &remappings, const std::string &name, uint32_t options=0)
ros.h
diffbot_base::DiffBotHWInterface::read
virtual void read(const ros::Time &time, const ros::Duration &period) override
Read data from the robot hardware.
Definition: diffbot_hw_interface.cpp:136
diffbot_base::DiffBotHWInterface::write
virtual void write(const ros::Time &time, const ros::Duration &period)
Write commands to the robot hardware.
Definition: diffbot_hw_interface.cpp:163
ros::AsyncSpinner
controller_manager.h
ros::ok
ROSCPP_DECL bool ok()
spinner
void spinner()
argv
argv
nh
ros::NodeHandle nh
Definition: main.cpp:8
diffbot_hw_interface.h
ros::Rate::sleep
bool sleep()
diffbot_base::DiffBotHWInterface
Hardware interface for a robot.
Definition: diffbot_hw_interface.h:32
ros::Time
ros::Rate
ros::Duration
controller_manager::ControllerManager::update
void update(const ros::Time &time, const ros::Duration &period, bool reset_controllers=false)
ros::NodeHandle
ros::Time::now
static Time now()
main
int main(int argc, char **argv)
Definition: diffbot_base.cpp:5


diffbot_base
Author(s):
autogenerated on Thu Sep 7 2023 02:35:23