src
ros_lib
examples
twistdrive.cpp
Go to the documentation of this file.
1
/*
2
* Rosserial Vex Cortex keyboard/phone driving demo
3
*
4
* For keyboard
5
* ---------
6
* install the keyboard twist publisher: http://wiki.ros.org/teleop_twist_keyboard
7
*
8
* run the command described in the link, and key control will work on the robot!
9
* press center key to re-center.
10
*
11
* For phone
12
* --------
13
* Install ROS Nav Map from the google play store
14
* follow setup instructions, use the joypad!
15
*/
16
17
#include <ros.h>
18
#include "geometry_msgs/Twist.h"
19
20
inline
void
handleControl
(
const
geometry_msgs::Twist& t){
21
// power motors using the message event!
22
// (default configuration is for a clawbot set up in the standard fashion).
23
motorSet(1, -(
int
) (100 * t.linear.x + 50 * t.angular.z));
24
motorSet(10, (
int
) (100 * t.linear.x - 50 * t.angular.z));
25
}
26
27
// called from opcontrol.cpp
28
inline
void
setup
()
29
{
30
// debug logging
31
vexroslog
(
"\n\n\n\n\r\t\tROSserial for VEX Cortex V2 - June 2018 - TWIST\n\n\n\n\n\r"
);
32
33
// make a node handle object and a subscriber for the Twist message.
34
ros::NodeHandle
nh;
35
ros::Subscriber<geometry_msgs::Twist>
sub(
"cmd_vel\0"
, &
handleControl
);
36
37
// set up rosserial, and prepare to publish the chatter message
38
nh.initNode();
39
nh.
subscribe
(sub);
40
41
// message data variable.
42
while
(1) {
43
44
// send a message about the time!
45
nh.spinOnce();
46
delay(20);
47
}
48
}
handleControl
void handleControl(const geometry_msgs::Twist &t)
Definition:
twistdrive.cpp:20
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())
vexroslog
#define vexroslog(fmtstr,...)
Definition:
logger.h:25
setup
void setup()
Definition:
twistdrive.cpp:28
ros::Subscriber
ros::NodeHandle
rosserial_vex_cortex
Author(s): Cannon
autogenerated on Wed Mar 2 2022 00:58:20