Main Page
Namespaces
Classes
Files
File List
File Members
ric_interface_node.cpp
Go to the documentation of this file.
1
#include <
ros/ros.h
>
2
3
#include <
ric_interface/ric_interface.h
>
4
5
ric_interface::RicInterface
bm
;
6
7
int
main
(
int
argc,
char
**argv)
8
{
9
ros::init
(argc, argv,
"ric_interface_node"
);
10
ros::NodeHandle
nh;
11
12
bm.
connect
(
"/dev/armadillo2/RICBOARD"
);
13
14
ros::Time
prev_time =
ros::Time::now
();
15
while
(
ros::ok
())
16
{
17
bm.
loop
();
18
if
(
ros::Time::now
() - prev_time >=
ros::Duration
(0.1))
19
{
20
//fprintf(stderr, "here\n");
21
ric_interface::protocol::servo
actu_pkg;
22
actu_pkg.
cmd
=2000;
23
bm.
writeCmd
(actu_pkg,
sizeof
(
ric_interface::protocol::servo
),
ric_interface::protocol::Type::SERVO
);
24
prev_time =
ros::Time::now
();
25
}
26
ros::spinOnce
;
27
}
28
}
29
30
31
32
ros::NodeHandle
ros::Time
ric_interface::protocol::servo
Definition:
protocol.h:117
ric_interface::protocol::servo::cmd
uint16_t cmd
Definition:
protocol.h:120
ros::init
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
ric_interface::RicInterface::connect
void connect(std::string port)
Definition:
ric_interface.cpp:14
bm
ric_interface::RicInterface bm
Definition:
ric_interface_node.cpp:5
ros::ok
ROSCPP_DECL bool ok()
main
int main(int argc, char **argv)
Definition:
ric_interface_node.cpp:7
ros.h
ros::Duration
ros::Time::now
static Time now()
ric_interface::RicInterface::writeCmd
void writeCmd(const protocol::actuator &actu_pkg, size_t size, protocol::Type type)
Definition:
ric_interface.cpp:156
ric_interface::RicInterface::loop
void loop()
Definition:
ric_interface.cpp:24
ros::spinOnce
ROSCPP_DECL void spinOnce()
ric_interface::RicInterface
Definition:
ric_interface.h:18
ric_interface::protocol::Type::SERVO
ric_interface.h
ric_interface
Author(s):
autogenerated on Wed Jan 3 2018 03:48:20