Fawkes API  Fawkes Development Version
 All Classes Namespaces Functions Variables Typedefs Enumerations Enumerator Friends Groups Pages
cmdvel_thread.cpp
1 /***************************************************************************
2  * cmdvel_plugin.cpp - Translate ROS Twist messages to Navgiator transrot
3  *
4  * Created: Fri Jun 1 13:29:39 CEST 2012
5  * Copyright 2012 Sebastian Reuter
6  ****************************************************************************/
7 
8 /* This program is free software; you can redistribute it and/or modify
9  * it under the terms of the GNU General Public License as published by
10  * the Free Software Foundation; either version 2 of the License, or
11  * (at your option) any later version.
12  *
13  * This program is distributed in the hope that it will be useful,
14  * but WITHOUT ANY WARRANTY; without even the implied warranty of
15  * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
16  * GNU Library General Public License for more details.
17  *
18  * Read the full text in the LICENSE.GPL file in the doc directory.
19  */
20 
21 #include "cmdvel_thread.h"
22 #include <interfaces/MotorInterface.h>
23 #include <ros/node_handle.h>
24 #include <geometry_msgs/Twist.h>
25 
26 //using namespace ros;
27 using namespace fawkes;
28 
29 /** @class ROSCmdVelThread "cmdvel_thread.h"
30  * Thread to translate ROS twist messages to navigator transrot messages.
31  * @author Sebastian Reuter
32  */
33 
34 /** Constructor. */
36  : Thread("ROSCmdVelThread", Thread::OPMODE_WAITFORWAKEUP)
37 {
38 }
39 
40 void
42 {
43  std::string motor_if_id = config->get_string("/ros/cmdvel/motor_interface_id");
44  motor_if_ = blackboard->open_for_reading<MotorInterface>(motor_if_id.c_str());
45  sub_ = rosnode->subscribe("cmd_vel", 10, &ROSCmdVelThread::twist_msg_cb, this);
46 }
47 
48 void
49 ROSCmdVelThread::twist_msg_cb(const geometry_msgs::Twist::ConstPtr &msg)
50 {
51  send_transrot(msg->linear.x, msg->linear.y, msg->angular.z);
52 }
53 
54 bool
56 {
57  stop();
58  return true;
59 }
60 
61 void
63 {
64  blackboard->close(motor_if_);
65  sub_.shutdown();
66 }
67 
68 void
69 ROSCmdVelThread::send_transrot(float vx, float vy, float omega)
70 {
72  new MotorInterface::TransRotMessage(vx, vy, omega);
73  motor_if_->msgq_enqueue(msg);
74 }
75 
76 void
77 ROSCmdVelThread::stop()
78 {
79  send_transrot(0., 0., 0.);
80 }
81 
82 void
84 {
85 }