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
VEXProMotor13Subscribe
VEXProMotor13Subscribe.cpp
Go to the documentation of this file.
1
/*
2
* VEXProMotor13Subscribe.cpp
3
* Control motor 13 speed by publishing the desired speed on a ros topic with e.g.
4
* $ rostopic pub my_topic std_msgs/Int32 120
5
*/
6
7
#include <ros.h>
8
#include <std_msgs/Int32.h>
9
#include <stdio.h>
10
#include "qemotoruser.h"
11
12
/*
13
* Control motor 13 speed by publishing the desired speed on a ros topic with e.g.
14
* $ rostopic pub my_topic std_msgs/Int32 120
15
* The range of speeds is -255 to +255 (corresponding to full reverse to full forward).
16
* Publish negative speeds using the syntax below:
17
* $ rostopic pub my_topic std_msgs/Int32 -- -120
18
* (This construct tells the shell to feed everything after -- directly to rostopic.)
19
*/
20
21
ros::NodeHandle
nh
;
22
CQEMotorUser &
motor
= CQEMotorUser::GetRef();
23
char
*
rosSrvrIp
=
"192.168.11.9"
;
24
25
void
messageCb
(
const
std_msgs::Int32& motor13_msg){
26
int
speed = motor13_msg.data;
27
printf(
"Received subscribed motor speed %d\n"
, speed);
28
motor
.SetPWM(0, speed);
29
}
30
ros::Subscriber<std_msgs::Int32>
sub
(
"motor13"
,
messageCb
);
31
32
33
int
main
()
34
{
35
//nh.initNode();
36
nh
.initNode(
rosSrvrIp
);
37
nh
.
subscribe
(
sub
);
38
39
while
(1) {
40
sleep(1);
41
nh
.spinOnce();
42
}
43
}
messageCb
void messageCb(const std_msgs::Int32 &motor13_msg)
Definition:
VEXProMotor13Subscribe.cpp:25
nh
ros::NodeHandle nh
Definition:
VEXProMotor13Subscribe.cpp:21
rosSrvrIp
char * rosSrvrIp
Definition:
VEXProMotor13Subscribe.cpp:23
motor
CQEMotorUser & motor
Definition:
VEXProMotor13Subscribe.cpp:22
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())
main
int main()
Definition:
VEXProMotor13Subscribe.cpp:33
sub
ros::Subscriber< std_msgs::Int32 > sub("motor13", messageCb)
ros::Subscriber
ros::NodeHandle
rosserial_embeddedlinux
Author(s): Paul Bouchier
autogenerated on Wed Mar 2 2022 00:58:06