Main Page
Namespaces
Namespace List
Namespace Members
All
Functions
Variables
Typedefs
Classes
Class List
Class Members
All
Functions
Variables
Files
File List
File Members
All
b
c
d
e
g
h
i
m
n
r
s
u
Functions
Variables
c
g
h
i
m
n
r
s
Macros
src
examples
VEXProServoSubscribe
VEXProServoSubscribe.cpp
Go to the documentation of this file.
1
/*
2
* VEXProServoSubscribe.cpp
3
*
4
* Created on: Jul 12, 2012
5
* Author: bouchier
6
* Drives a servo or motor on VEXPro motor1 connection to the requested value: 0 - 255
7
* that is received on subscribed topic servo1
8
*/
9
10
#include <ros.h>
11
#include <std_msgs/Int32.h>
12
#include <iostream>
13
#include <qeservo.h>
14
using namespace
std
;
15
16
ros::NodeHandle
nh
;
17
CQEServo &
servo
= CQEServo::GetRef();
18
char
*
rosSrvrIp
=
"192.168.15.149"
;
19
20
void
messageCb
(
const
std_msgs::Int32& servo1_msg){
21
int
position = servo1_msg.data;
22
printf(
"Received subscribed servo position %d\n"
, position);
23
servo
.SetCommand(0, position);
24
}
25
ros::Subscriber<std_msgs::Int32>
sub
(
"servo1"
,
messageCb
);
26
27
int
main
() {
28
//nh.initNode();
29
nh
.initNode(
rosSrvrIp
);
30
nh
.
subscribe
(
sub
);
31
32
while
(1) {
33
sleep(1);
34
nh
.spinOnce();
35
}
36
}
nh
ros::NodeHandle nh
Definition:
VEXProServoSubscribe.cpp:16
rosSrvrIp
char * rosSrvrIp
Definition:
VEXProServoSubscribe.cpp:18
main
int main()
Definition:
VEXProServoSubscribe.cpp:27
ros::NodeHandle::subscribe
Subscriber subscribe(const std::string &topic, uint32_t queue_size, const boost::function< void(C)> &callback, const VoidConstPtr &tracked_object=VoidConstPtr(), const TransportHints &transport_hints=TransportHints())
servo
CQEServo & servo
Definition:
VEXProServoSubscribe.cpp:17
sub
ros::Subscriber< std_msgs::Int32 > sub("servo1", messageCb)
std
messageCb
void messageCb(const std_msgs::Int32 &servo1_msg)
Definition:
VEXProServoSubscribe.cpp:20
ros::Subscriber
ros::NodeHandle
rosserial_embeddedlinux
Author(s): Paul Bouchier
autogenerated on Wed Mar 2 2022 00:58:06