Main Page
Namespaces
Classes
Files
File List
File Members
src
fake_joint_driver_node.cpp
Go to the documentation of this file.
1
9
#include "
ros/ros.h
"
10
#include "
controller_manager/controller_manager.h
"
11
#include "
fake_joint_driver/fake_joint_driver.h
"
12
16
int
main
(
int
argc,
char
**argv)
17
{
18
// Init ROS node
19
ros::init
(argc, argv,
"fake_joint_driver"
);
20
ros::NodeHandle
nh;
21
22
// Create hardware interface
23
FakeJointDriver
robot;
24
// Connect to controller manager
25
controller_manager::ControllerManager
cm(&robot, nh);
26
27
// Set spin ratge
28
ros::Rate
rate(1.0 /
ros::Duration
(0.010).toSec());
29
ros::AsyncSpinner
spinner
(1);
30
spinner.
start
();
31
32
while
(
ros::ok
())
33
{
34
robot.
update
();
35
cm.
update
(
ros::Time::now
(),
ros::Duration
(0.010));
36
rate.
sleep
();
37
}
38
spinner.
stop
();
39
40
return
0;
41
}
controller_manager::ControllerManager
ros::NodeHandle
ros::init
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
ros::Rate
fake_joint_driver.h
FakeJointDriver
Definition:
fake_joint_driver.h:14
spinner
void spinner()
ros::AsyncSpinner::start
void start()
ros::ok
ROSCPP_DECL bool ok()
ros::Rate::sleep
bool sleep()
ros.h
FakeJointDriver::update
void update(void)
Update function to call all of the update function of motors.
Definition:
fake_joint_driver.cpp:122
ros::Duration
controller_manager.h
ros::Time::now
static Time now()
controller_manager::ControllerManager::update
void update(const ros::Time &time, const ros::Duration &period, bool reset_controllers=false)
ros::AsyncSpinner::stop
void stop()
ros::AsyncSpinner
main
int main(int argc, char **argv)
Main function.
Definition:
fake_joint_driver_node.cpp:16
fake_joint_driver
Author(s): Ryosuke Tajima
autogenerated on Thu Dec 19 2019 03:31:40