obstacle_avoidance.cpp
Go to the documentation of this file.
1 /******************************************************************************
2  STDR Simulator - Simple Two DImensional Robot Simulator
3  Copyright (C) 2013 STDR Simulator
4  This program is free software; you can redistribute it and/or modify
5  it under the terms of the GNU General Public License as published by
6  the Free Software Foundation; either version 3 of the License, or
7  (at your option) any later version.
8  This program is distributed in the hope that it will be useful,
9  but WITHOUT ANY WARRANTY; without even the implied warranty of
10  MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
11  GNU General Public License for more details.
12  You should have received a copy of the GNU General Public License
13  along with this program; if not, write to the Free Software Foundation,
14  Inc., 51 Franklin Street, Fifth Floor, Boston, MA 02110-1301 USA
15 
16  Authors :
17  * Manos Tsardoulias, etsardou@gmail.com
18  * Aris Thallas, aris.thallas@gmail.com
19  * Chris Zalidis, zalidis@gmail.com
20 ******************************************************************************/
22 
27 namespace stdr_samples
28 {
36  {
37  if(argc != 3)
38  {
39  ROS_ERROR(
40  "Usage : stdr_obstacle avoidance <robot_frame_id> <laser_frame_id>");
41  exit(0);
42  }
43  laser_topic_ = std::string("/") +
44  std::string(argv[1]) + std::string("/") + std::string(argv[2]);
45  speeds_topic_ = std::string("/") +
46  std::string(argv[1]) + std::string("/cmd_vel");
47 
49  laser_topic_.c_str(),
50  1,
52  this);
53 
54  cmd_vel_pub_ = n_.advertise<geometry_msgs::Twist>(speeds_topic_.c_str(), 1);
55  }
56 
62  {
63 
64  }
65 
71  void ObstacleAvoidance::callback(const sensor_msgs::LaserScan& msg)
72  {
73  scan_ = msg;
74  float linear = 0, rotational = 0;
75  for(unsigned int i = 0 ; i < scan_.ranges.size() ; i++)
76  {
77  float real_dist = scan_.ranges[i];
78  linear -= cos(scan_.angle_min + i * scan_.angle_increment)
79  / (1.0 + real_dist * real_dist);
80  rotational -= sin(scan_.angle_min + i * scan_.angle_increment)
81  / (1.0 + real_dist * real_dist);
82  }
83  geometry_msgs::Twist cmd;
84 
85  linear /= scan_.ranges.size();
86  rotational /= scan_.ranges.size();
87 
88  //~ ROS_ERROR("%f %f",linear,rotational);
89 
90  if(linear > 0.3)
91  {
92  linear = 0.3;
93  }
94  else if(linear < -0.3)
95  {
96  linear = -0.3;
97  }
98 
99  cmd.linear.x = 0.3 + linear;
100  cmd.angular.z = rotational;
101  cmd_vel_pub_.publish(cmd);
102  }
103 }
ros::NodeHandle n_
The laser topic.
std::string laser_topic_
The speeds topic.
void publish(const boost::shared_ptr< M > &message) const
Subscriber subscribe(const std::string &topic, uint32_t queue_size, void(T::*fp)(M), T *obj, const TransportHints &transport_hints=TransportHints())
ros::Subscriber subscriber_
The ROS node handle.
sensor_msgs::LaserScan scan_
< The ros laser scan msg
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
void callback(const sensor_msgs::LaserScan &msg)
Callback for the ros laser message.
ObstacleAvoidance(int argc, char **argv)
Default contructor.
std::string speeds_topic_
The twist publisher.
#define ROS_ERROR(...)
~ObstacleAvoidance(void)
Default destructor.
The main namespace for STDR Samples.


stdr_samples
Author(s): Manos Tsardoulias, Chris Zalidis, Aris Thallas
autogenerated on Mon Jun 10 2019 15:15:03