1 #include <nav_msgs/GridCells.h> 74 double tx = cos(tw) + 1;
76 double tr = ((tx*tx)+(ty*ty))/(ty+ty);
77 std::vector<geometry_msgs::Point32> points;
81 double x = tr * sin(alpha);
82 double y = tr * (1.0 - cos(alpha));
83 geometry_msgs::Point32 p;
92 sensor_msgs::PointCloud* flcloud =
new sensor_msgs::PointCloud();
95 flcloud->points.resize(points.size());
98 sensor_msgs::PointCloud* frcloud =
new sensor_msgs::PointCloud();
101 frcloud->points.resize(points.size());
104 sensor_msgs::PointCloud* blcloud =
new sensor_msgs::PointCloud();
107 blcloud->points.resize(points.size());
110 sensor_msgs::PointCloud* brcloud =
new sensor_msgs::PointCloud();
113 brcloud->points.resize(points.size());
115 for(
unsigned int j = 0; j < points.size(); j++)
117 flcloud->points[j] = points[j];
118 frcloud->points[j] = points[j];
119 blcloud->points[j] = points[j];
120 brcloud->points[j] = points[j];
122 frcloud->points[j].y *= -1;
123 blcloud->points[j].x *= -1;
124 brcloud->points[j].x *= -1;
125 brcloud->points[j].y *= -1;
129 mTrajTable[(3 * LUT_RESOLUTION + 1) - i] = blcloud;
130 mTrajTable[(3 * LUT_RESOLUTION + 1) + i] = brcloud;
134 geometry_msgs::Point32 p;
139 sensor_msgs::PointCloud* turn =
new sensor_msgs::PointCloud();
142 turn->points.resize(1);
147 sensor_msgs::PointCloud* fscloud =
new sensor_msgs::PointCloud();
150 fscloud->points.resize(straight_len);
152 sensor_msgs::PointCloud* bscloud =
new sensor_msgs::PointCloud();
155 bscloud->points.resize(straight_len);
157 for(
int i = 0; i < straight_len; i++)
159 fscloud->points[i] = p;
160 bscloud->points[i] = p;
161 bscloud->points[i].x *= -1;
173 for(
int i = 0; i < (LUT_RESOLUTION * 4) + 2; i++)
177 ROS_ERROR(
"Table entry %d has not been initialized!", i);
184 if(msg->Turn < -1 || msg->Turn > 1)
204 boost::unique_lock<costmap_2d::Costmap2D::mutex_t> lock(*(
mCostmap->
getMutex()));
205 double bestDirection,
d;
213 if(d < -0.2) d = -0.2;
215 mCurrentDirection += d;
231 sensor_msgs::PointCloud transformedCloud;
248 if(freeCells == transformedCloud.points.size() && safeVelocity < 0.5)
251 if(freeSpace < 0.3 && freeCells < transformedCloud.points.size())
259 if(safeVelocity < 0.1)
275 nav_msgs::GridCells route_msg;
282 route_msg.cells.resize(freeCells);
283 for(
int i = 0; i < freeCells; i++)
285 route_msg.cells[i].x = transformedCloud.points[i].x;
286 route_msg.cells[i].y = transformedCloud.points[i].y;
287 route_msg.cells[i].z = transformedCloud.points[i].z;
293 sensor_msgs::PointCloud transformedPlanCloud;
304 nav_msgs::GridCells plan_msg;
305 plan_msg.header = route_msg.header;
311 plan_msg.cells.resize(freeSpacePlan);
312 for(
int i = 0; i < freeSpacePlan; i++)
314 plan_msg.cells[i].x = transformedPlanCloud.points[i].x;
315 plan_msg.cells[i].y = transformedPlanCloud.points[i].y;
316 plan_msg.cells[i].z = transformedPlanCloud.points[i].z;
322 geometry_msgs::Twist controlMsg;
326 if(velocity > safeVelocity)
328 ROS_DEBUG(
"Desired velocity of %.2f is limited to %.2f", velocity, safeVelocity);
329 velocity = safeVelocity;
330 }
else if(velocity < -safeVelocity)
332 ROS_DEBUG(
"Desired velocity of %.2f is limited to %.2f", velocity, -safeVelocity);
333 velocity = -safeVelocity;
335 controlMsg.linear.x = velocity;
336 controlMsg.angular.z = 0;
339 controlMsg.linear.x = 0;
345 double r = ((x*x) + (y*y)) / (2*x);
346 double abs_r = (r > 0) ? r : -r;
347 velocity /= (1 + (1.0/abs_r));
348 if(velocity > safeVelocity)
350 ROS_DEBUG(
"Desired velocity of %.2f is limited to %.2f", velocity, safeVelocity);
351 velocity = safeVelocity;
352 }
else if(velocity < -safeVelocity)
354 ROS_DEBUG(
"Desired velocity of %.2f is limited to %.2f", velocity, -safeVelocity);
355 velocity = -safeVelocity;
358 controlMsg.linear.x = velocity;
359 controlMsg.angular.z = -1.0 / r * controlMsg.linear.x;
367 int length = cloud->points.size();
369 for(
int i = 0; i < length; i++)
390 sensor_msgs::PointCloud* originalCloud =
getPointCloud(direction, velocity);
391 sensor_msgs::PointCloud transformedCloud;
402 double valueSafety = 0.0;
403 double valueEscape = 0.0;
404 double valueConformance = 0.0;
405 double valueContinue = 0.0;
408 double safe_max = 0.0;
409 double cost_max = 0.0;
410 double cost_start = 1.0;
413 int length = transformedCloud.points.size();
414 for(
int i = 0; i < length; i++)
418 if(
mCostmap->
worldToMap(transformedCloud.points[i].x, transformedCloud.points[i].y, mx, my))
428 cost_start = cell_cost;
429 double cost = cell_cost * decay;
430 double safe = (cost_start - cell_cost) * decay * 2.0;
432 if(cost > cost_max) cost_max = cost;
433 if(safe > safe_max) safe_max = safe;
438 double action_value = 0.0;
439 double normFactor = 0.0;
442 valueSafety = 1.0 - cost_max;
447 valueEscape = safe_max;
455 valueContinue = 1.0 - (valueContinue * valueContinue);
459 valueConformance = 0.5 * cos(corr) + 0.5;
467 action_value /= normFactor;
471 geometry_msgs::Vector3 cost_msg;
472 cost_msg.x = valueSafety;
473 cost_msg.y = valueEscape;
474 cost_msg.z = valueConformance;
481 double diff(
double v1,
double v2)
491 double best_dir = -1.0;
492 double best_value = 0.0;
499 if(value > best_value)
511 if(direction < -1) direction = -1;
512 if(direction > 1) direction = 1;
ros::Publisher mPlanPublisher
void executeCommand()
Generates and sends Twist-Message to Robot This is the Operator's core function and should be called ...
ros::Publisher mCostPublisher
void publish(const boost::shared_ptr< M > &message) const
The core of a ROS node to provide purely reactive obstacle avoidance The RobotOperator is supposed to...
ros::Subscriber mCommandSubscriber
void initTrajTable()
Initializes look-up tables This calculates the trajectories of all possible direction commands...
Subscriber subscribe(const std::string &topic, uint32_t queue_size, void(T::*fp)(M), T *obj, const TransportHints &transport_hints=TransportHints())
sensor_msgs::PointCloud * getPointCloud(double direction, double velocity)
Get the trajectory defined by the given movement command.
double evaluateAction(double direction, double velocity, bool debug=false)
Calculate the action value of a given command.
costmap_2d::Costmap2D * mCostmap
TFSIMD_FORCE_INLINE const tfScalar & y() const
ros::Publisher mTrajectoryPublisher
int calculateFreeSpace(sensor_msgs::PointCloud *cloud)
Calculates the distance the robot can move following the given trajectory.
unsigned char getCost(unsigned int mx, unsigned int my) const
void receiveCommand(const nav2d_operator::cmd::ConstPtr &msg)
Callback function to receive move commands.
static const unsigned char INSCRIBED_INFLATED_OBSTACLE
#define ROS_WARN_THROTTLE(period,...)
costmap_2d::Costmap2DROS * mLocalMap
bool param(const std::string ¶m_name, T ¶m_val, const T &default_val) const
TFSIMD_FORCE_INLINE const tfScalar & x() const
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
ros::Publisher mControlPublisher
double diff(double v1, double v2)
TFSIMD_FORCE_INLINE tfScalar length(const Quaternion &q)
std::string mOdometryFrame
double getResolution() const
double findBestDirection()
Evaluates all possible directions with a fixed resolution.
tf::TransformListener mTfListener
bool worldToMap(double wx, double wy, unsigned int &mx, unsigned int &my) const
unsigned int mRecoverySteps
sensor_msgs::PointCloud * mTrajTable[(LUT_RESOLUTION *4)+2]