Main Page
Namespaces
Namespace List
Namespace Members
All
d
k
u
Enumerations
Enumerator
k
u
Classes
Class List
Class Hierarchy
Class Members
All
b
c
d
e
g
h
i
j
l
m
n
p
r
s
t
u
v
w
z
~
Functions
b
d
g
i
j
l
m
p
r
s
w
~
Variables
b
c
d
e
g
h
i
j
l
m
n
p
r
s
t
u
v
w
z
Files
File List
File Members
All
Functions
Macros
src
dynamixel_interface_main.cpp
Go to the documentation of this file.
1
51
#include <
dynamixel_interface/dynamixel_interface_controller.h
>
52
#include <
ros/ros.h
>
53
55
int
main
(
int
argc,
char
**argv)
56
{
57
// ros initialise
58
ros::init
(argc, argv,
"dynamixel_interface_node"
);
59
60
// create controller
61
dynamixel_interface::DynamixelInterfaceController
controller;
62
63
// parse params
64
if
(!controller.
parseParameters
())
65
{
66
return
1;
67
}
68
69
// intialise
70
if
(!controller.
initialise
())
71
{
72
return
2;
73
}
74
75
// initialise rate controller
76
ros::Rate
rate(controller.
getLoopRate
());
77
78
// Loop and process
79
while
(
ros::ok
())
80
{
81
controller.
loop
();
82
83
ros::spinOnce
();
84
rate.
sleep
();
85
}
86
87
return
0;
88
}
dynamixel_interface::DynamixelInterfaceController::parseParameters
bool parseParameters(void)
Definition:
dynamixel_interface_controller.cpp:131
ros::init
ROSCPP_DECL void init(const M_string &remappings, const std::string &name, uint32_t options=0)
ros.h
ros::spinOnce
ROSCPP_DECL void spinOnce()
ros::ok
ROSCPP_DECL bool ok()
dynamixel_interface_controller.h
Defines the dynamixel controller class and the types used therein.
dynamixel_interface::DynamixelInterfaceController::initialise
bool initialise()
Definition:
dynamixel_interface_controller.cpp:571
ros::Rate::sleep
bool sleep()
main
int main(int argc, char **argv)
main
Definition:
dynamixel_interface_main.cpp:55
dynamixel_interface::DynamixelInterfaceController::getLoopRate
double getLoopRate(void)
Definition:
dynamixel_interface_controller.h:174
ros::Rate
dynamixel_interface::DynamixelInterfaceController
Definition:
dynamixel_interface_controller.h:148
dynamixel_interface::DynamixelInterfaceController::loop
void loop(void)
Definition:
dynamixel_interface_controller.cpp:958
dynamixel_interface
Author(s): Tom Molnar
autogenerated on Wed Mar 2 2022 00:13:19