Classes | |
| class | Agent | 
| struct | ConvexHullPoint | 
| struct | Line | 
| struct | Obstacle | 
| class | ROSAgent | 
| class | Vector2 | 
| struct | VelocitySample | 
| struct | VO | 
Typedefs | |
| typedef boost::shared_ptr< Agent > | AgentPtr | 
| typedef boost::shared_ptr < ROSAgent >  | ROSAgentPtr | 
Functions | |
| double | abs (const Vector2 &vector) | 
| double | absSqr (const Vector2 &vector) | 
| void | addAccelerationConstraintsXY (double max_vel_x, double acc_lim_x, double max_vel_y, double acc_lim_y, Vector2 cur_vel, double heading, double sim_period, bool holo_robot, std::vector< Line > &additional_orca_lines) | 
| void | addCircleLineIntersections (std::vector< VelocitySample > &samples, const Vector2 &pref_vel, double max_speed, bool use_truncation, const Vector2 &point, const Vector2 &dir) | 
| void | addIntersectPoint (std::vector< VelocitySample > &samples, const Vector2 &pref_vel, double max_speed, bool use_truncation, Vector2 point, const std::vector< VO > &truncated_vos) | 
| void | addMovementConstraintsDiff (double error, double T, double max_vel_x, double max_vel_th, double heading, double v_max_ang, std::vector< Line > &additional_orca_lines) | 
| void | addMovementConstraintsDiffSimple (double max_track_speed, double heading, std::vector< Line > &additional_orca_lines) | 
| void | addRayVelocitySamples (std::vector< VelocitySample > &samples, const Vector2 &pref_vel, Vector2 point1, Vector2 dir1, Vector2 point2, Vector2 dir2, double max_speed, int TYPE) | 
| void | amclPoseArrayWeightedCallback (const amcl::PoseArrayWeighted::ConstPtr &msg) | 
| double | angleBetween (const Vector2 &one, const Vector2 &two) | 
| double | atan (const Vector2 &vector) | 
| double | beta (double T, double theta, double v_max_ang) | 
| double | CalcArea (std::vector< Vector2 > list) | 
| Vector2 | calculateClearpathVelocity (std::vector< VelocitySample > &samples, const std::vector< VO > &truncated_vos, const std::vector< Line > &additional_constraints, const Vector2 &pref_vel, double max_speed, bool use_truncation) | 
| double | calculateMaxTrackSpeedAngle (double T, double theta, double error, double max_vel_x, double max_vel_th, double v_max_ang) | 
| Vector2 | calculateNewVelocitySampled (std::vector< VelocitySample > &samples, const std::vector< VO > &truncated_vos, const Vector2 &pref_vel, double max_speed, bool use_truncation) | 
| double | calculateVelCosts (const Vector2 &test_vel, const std::vector< VO > &truncated_vos, const Vector2 &pref_vel, double max_speed, bool use_truncation) | 
| double | calcVstar (double vh, double theta) | 
| double | calcVstarError (double T, double theta, double error) | 
| bool | compareConvexHullPointsPosition (const ConvexHullPoint &p1, const ConvexHullPoint &p2) | 
| bool | comparePoint (const Vector2 &p1, const Vector2 &p2) | 
| bool | compareVectorsLexigraphically (const ConvexHullPoint &v1, const ConvexHullPoint &v2) | 
| bool | compareVelocitySamples (const VelocitySample &p1, const VelocitySample &p2) | 
| void | computeNewLocUncertainty () | 
| void | computeNewMinkowskiFootprint () | 
| std::vector< ConvexHullPoint > | convexHull (std::vector< ConvexHullPoint > P, bool sorted) | 
| VO | createHRVO (Vector2 &position1, const std::vector< Vector2 > &footprint1, Vector2 &vel1, Vector2 &position2, const std::vector< Vector2 > &footprint2, Vector2 &vel2) | 
| VO | createHRVO (Vector2 &position1, double radius1, Vector2 &vel1, Vector2 &position2, double radius2, Vector2 &vel2) | 
| VO | createObstacleVO (Vector2 &position1, const std::vector< Vector2 > &footprint1, Vector2 &vel1, Vector2 &position2, const std::vector< Vector2 > &footprint2) | 
| VO | createObstacleVO (Vector2 &position1, double radius1, Vector2 &vel1, Vector2 &position2, double radius2) | 
| VO | createObstacleVO (Vector2 &position1, double radius1, const std::vector< Vector2 > &footprint1, Vector2 &obst1, Vector2 &obst2) | 
| Line | createOrcaLine (Agent *me, Agent *other, double trunc_time, double timestep, double left_pref, double cur_allowed_error) | 
| Line | createOrcaLine (double combinedRadius, const Vector2 &relativePosition, const Vector2 &me_vel, const Vector2 &other_vel, double trunc_time, double timestep, double left_pref, double cur_allowed_error, bool controlled) | 
| VO | createRVO (Vector2 &position1, const std::vector< Vector2 > &footprint1, Vector2 &vel1, Vector2 &position2, const std::vector< Vector2 > &footprint2, Vector2 &vel2) | 
| VO | createRVO (Vector2 &position1, double radius1, Vector2 &vel1, Vector2 &position2, double radius2, Vector2 &vel2) | 
| void | createSamplesWithinMovementConstraints (std::vector< VelocitySample > &samples, double cur_vel_x, double cur_vel_y, double cur_vel_theta, double acc_lim_x, double acc_lim_y, double acc_lim_theta, double min_vel_x, double max_vel_x, double min_vel_y, double max_vel_y, double min_vel_theta, double max_vel_theta, double heading, Vector2 pref_vel, double sim_period, int num_samples, bool holo_robot) | 
| Line | createStationaryAgent (Agent *me, Agent *other) | 
| VO | createTruncVO (VO &vo, double time) | 
| VO | createVO (Vector2 &position1, const std::vector< Vector2 > &footprint1, Vector2 &position2, const std::vector< Vector2 > &footprint2, Vector2 &vel2) | 
| VO | createVO (Vector2 &position1, const std::vector< Vector2 > &footprint1, Vector2 &vel1, Vector2 &position2, const std::vector< Vector2 > &footprint2, Vector2 &vel2, int TYPE) | 
| VO | createVO (Vector2 &position1, double radius1, Vector2 &vel1, Vector2 &position2, double radius2, Vector2 &vel2, int TYPE) | 
| VO | createVO (Vector2 &position1, double radius1, Vector2 &position2, double radius2, Vector2 &vel2) | 
| double | cross (const ConvexHullPoint &O, const ConvexHullPoint &A, const ConvexHullPoint &B) | 
| double | det (const Vector2 &vector1, const Vector2 &vector2) | 
| double | distSqPointLineSegment (const Vector2 &a, const Vector2 &b, const Vector2 &c) | 
| Computes the squared distance from a line segment with the specified endpoints to a specified point.   | |
| void | fillMarkerWithROSAgent (visualization_msgs::MarkerArray &marker, ROSAgent *agent, std::string base_frame, std::string name_space) | 
| double | gamma (double T, double theta, double error, double v_max_ang) | 
| Vector2 | intersectTwoLines (Vector2 point1, Vector2 dir1, Vector2 point2, Vector2 dir2) | 
| Vector2 | intersectTwoLines (Line line1, Line line2) | 
| bool | isInsideVO (VO vo, Vector2 point, bool use_truncation) | 
| bool | isWithinAdditionalConstraints (const std::vector< Line > &additional_constraints, const Vector2 &point) | 
| double | left (const Vector2 &pointLine, const Vector2 &dirLine, const Vector2 &point) | 
| bool | leftOf (const Vector2 &pointLine, const Vector2 &dirLine, const Vector2 &point) | 
| bool | linearProgram1 (const std::vector< Line > &lines, size_t lineNo, float radius, const Vector2 &optVelocity, bool dirOpt, Vector2 &result) | 
| size_t | linearProgram2 (const std::vector< Line > &lines, float radius, const Vector2 &optVelocity, bool dirOpt, Vector2 &result) | 
| void | linearProgram3 (const std::vector< Line > &lines, size_t numObstLines, size_t beginLine, float radius, Vector2 &result) | 
| std::vector< Vector2 > | minkowskiSum (const std::vector< Vector2 > polygon1, const std::vector< Vector2 > polygon2) | 
| Vector2 | normal (const Vector2 &vector) | 
| Vector2 | normalize (const Vector2 &vector) | 
| void | odomCallback (const nav_msgs::Odometry::ConstPtr &msg) | 
| Vector2 | operator* (float s, const Vector2 &vector) | 
| Vector2 | projectPointOnLine (const Vector2 &pointLine, const Vector2 &dirLine, const Vector2 &point) | 
| void | publishHoloSpeed (Vector2 pos, Vector2 vel, std::string base_frame, std::string name_space, ros::Publisher speed_pub) | 
| void | publishMePosition (ROSAgent *me, std::string base_frame, std::string name_space, ros::Publisher me_pub) | 
| void | publishNeighborPositions (std::vector< AgentPtr > &neighbors, std::string base_frame, std::string name_space, ros::Publisher neighbors_pub) | 
| void | publishObstacleLines (const std::vector< Obstacle > &obstacles_lines, std::string base_frame, std::string name_space, ros::Publisher line_pub) | 
| void | publishOrcaLines (const std::vector< Line > &orca_lines, Vector2 &position, std::string base_frame, std::string name_space, ros::Publisher line_pub) | 
| void | publishPoints (Vector2 &pos, const std::vector< VelocitySample > &points, std::string base_frame, std::string name_space, ros::Publisher samples_pub) | 
| void | publishVOs (Vector2 &pos, const std::vector< VO > &truncated_vos, bool use_truncation, std::string base_frame, std::string name_space, ros::Publisher vo_pub) | 
| bool | rightOf (const Vector2 &pointLine, const Vector2 &dirLine, const Vector2 &point) | 
| Vector2 | rotateVectorByAngle (double x, double y, double ang) | 
| Vector2 | rotateVectorByAngle (const Vector2 &vec, double ang) | 
| double | sign (double x) | 
| double | signedDistPointToLineSegment (const Vector2 &a, const Vector2 &b, const Vector2 &c) | 
| Computes the sign from a line connecting the specified points to a specified point.   | |
| double | sqr (double a) | 
Variables | |
| std::string | base_frame_ | 
| double | cur_loc_unc_radius_ | 
| double | eps_ | 
| geometry_msgs::PolygonStamped | footprint_msg_ | 
| double | footprint_radius_ | 
| std::string | global_frame_ | 
| std::vector< Vector2 > | minkowski_footprint_ | 
| std::string | odom_frame_ | 
| std::vector< std::pair< double,  geometry_msgs::PoseStamped > >  | pose_array_weighted_ | 
| double | radius_ | 
| tf::TransformListener * | tf_ | 
| typedef boost::shared_ptr<Agent> collvoid::AgentPtr | 
| typedef boost::shared_ptr<ROSAgent> collvoid::ROSAgentPtr | 
Definition at line 246 of file ROSAgent.h.
| double collvoid::abs | ( | const Vector2 & | vector | ) |  [inline] | 
        
| double collvoid::absSqr | ( | const Vector2 & | vector | ) |  [inline] | 
        
| void collvoid::addAccelerationConstraintsXY | ( | double | max_vel_x, | 
| double | acc_lim_x, | ||
| double | max_vel_y, | ||
| double | acc_lim_y, | ||
| Vector2 | cur_vel, | ||
| double | heading, | ||
| double | sim_period, | ||
| bool | holo_robot, | ||
| std::vector< Line > & | additional_orca_lines | ||
| ) | 
| void collvoid::addCircleLineIntersections | ( | std::vector< VelocitySample > & | samples, | 
| const Vector2 & | pref_vel, | ||
| double | max_speed, | ||
| bool | use_truncation, | ||
| const Vector2 & | point, | ||
| const Vector2 & | dir | ||
| ) | 
Definition at line 489 of file clearpath.cpp.
| void collvoid::addIntersectPoint | ( | std::vector< VelocitySample > & | samples, | 
| const Vector2 & | pref_vel, | ||
| double | max_speed, | ||
| bool | use_truncation, | ||
| Vector2 | point, | ||
| const std::vector< VO > & | truncated_vos | ||
| ) | 
| void collvoid::addMovementConstraintsDiff | ( | double | error, | 
| double | T, | ||
| double | max_vel_x, | ||
| double | max_vel_th, | ||
| double | heading, | ||
| double | v_max_ang, | ||
| std::vector< Line > & | additional_orca_lines | ||
| ) | 
| void collvoid::addMovementConstraintsDiffSimple | ( | double | max_track_speed, | 
| double | heading, | ||
| std::vector< Line > & | additional_orca_lines | ||
| ) | 
| void collvoid::addRayVelocitySamples | ( | std::vector< VelocitySample > & | samples, | 
| const Vector2 & | pref_vel, | ||
| Vector2 | point1, | ||
| Vector2 | dir1, | ||
| Vector2 | point2, | ||
| Vector2 | dir2, | ||
| double | max_speed, | ||
| int | TYPE | ||
| ) | 
Definition at line 516 of file clearpath.cpp.
| void collvoid::amclPoseArrayWeightedCallback | ( | const amcl::PoseArrayWeighted::ConstPtr & | msg | ) | 
Definition at line 183 of file helper.cpp.
| double collvoid::angleBetween | ( | const Vector2 & | one, | 
| const Vector2 & | two | ||
| ) |  [inline] | 
        
| double collvoid::atan | ( | const Vector2 & | vector | ) |  [inline] | 
        
| double collvoid::beta | ( | double | T, | 
| double | theta, | ||
| double | v_max_ang | ||
| ) | 
| double collvoid::CalcArea | ( | std::vector< Vector2 > | list | ) | 
Definition at line 275 of file helper.cpp.
| Vector2 collvoid::calculateClearpathVelocity | ( | std::vector< VelocitySample > & | samples, | 
| const std::vector< VO > & | truncated_vos, | ||
| const std::vector< Line > & | additional_constraints, | ||
| const Vector2 & | pref_vel, | ||
| double | max_speed, | ||
| bool | use_truncation | ||
| ) | 
Definition at line 669 of file clearpath.cpp.
| double collvoid::calculateMaxTrackSpeedAngle | ( | double | T, | 
| double | theta, | ||
| double | error, | ||
| double | max_vel_x, | ||
| double | max_vel_th, | ||
| double | v_max_ang | ||
| ) | 
| Vector2 collvoid::calculateNewVelocitySampled | ( | std::vector< VelocitySample > & | samples, | 
| const std::vector< VO > & | truncated_vos, | ||
| const Vector2 & | pref_vel, | ||
| double | max_speed, | ||
| bool | use_truncation | ||
| ) | 
Definition at line 627 of file clearpath.cpp.
| double collvoid::calculateVelCosts | ( | const Vector2 & | test_vel, | 
| const std::vector< VO > & | truncated_vos, | ||
| const Vector2 & | pref_vel, | ||
| double | max_speed, | ||
| bool | use_truncation | ||
| ) | 
Definition at line 655 of file clearpath.cpp.
| double collvoid::calcVstar | ( | double | vh, | 
| double | theta | ||
| ) | 
| double collvoid::calcVstarError | ( | double | T, | 
| double | theta, | ||
| double | error | ||
| ) | 
| bool collvoid::compareConvexHullPointsPosition | ( | const ConvexHullPoint & | p1, | 
| const ConvexHullPoint & | p2 | ||
| ) | 
Definition at line 59 of file helper.cpp.
| bool collvoid::comparePoint | ( | const Vector2 & | p1, | 
| const Vector2 & | p2 | ||
| ) | 
Definition at line 63 of file helper.cpp.
| bool collvoid::compareVectorsLexigraphically | ( | const ConvexHullPoint & | v1, | 
| const ConvexHullPoint & | v2 | ||
| ) | 
Definition at line 843 of file clearpath.cpp.
| bool collvoid::compareVelocitySamples | ( | const VelocitySample & | p1, | 
| const VelocitySample & | p2 | ||
| ) | 
Definition at line 883 of file clearpath.cpp.
| void collvoid::computeNewLocUncertainty | ( | ) | 
Definition at line 68 of file helper.cpp.
Definition at line 105 of file helper.cpp.
| std::vector< ConvexHullPoint > collvoid::convexHull | ( | std::vector< ConvexHullPoint > | P, | 
| bool | sorted | ||
| ) | 
Definition at line 854 of file clearpath.cpp.
| VO collvoid::createHRVO | ( | Vector2 & | position1, | 
| const std::vector< Vector2 > & | footprint1, | ||
| Vector2 & | vel1, | ||
| Vector2 & | position2, | ||
| const std::vector< Vector2 > & | footprint2, | ||
| Vector2 & | vel2 | ||
| ) | 
Definition at line 315 of file clearpath.cpp.
| VO collvoid::createHRVO | ( | Vector2 & | position1, | 
| double | radius1, | ||
| Vector2 & | vel1, | ||
| Vector2 & | position2, | ||
| double | radius2, | ||
| Vector2 & | vel2 | ||
| ) | 
Definition at line 423 of file clearpath.cpp.
| VO collvoid::createObstacleVO | ( | Vector2 & | position1, | 
| const std::vector< Vector2 > & | footprint1, | ||
| Vector2 & | vel1, | ||
| Vector2 & | position2, | ||
| const std::vector< Vector2 > & | footprint2 | ||
| ) | 
| VO collvoid::createObstacleVO | ( | Vector2 & | position1, | 
| double | radius1, | ||
| Vector2 & | vel1, | ||
| Vector2 & | position2, | ||
| double | radius2 | ||
| ) | 
| VO collvoid::createObstacleVO | ( | Vector2 & | position1, | 
| double | radius1, | ||
| const std::vector< Vector2 > & | footprint1, | ||
| Vector2 & | obst1, | ||
| Vector2 & | obst2 | ||
| ) | 
Definition at line 78 of file clearpath.cpp.
| Line collvoid::createOrcaLine | ( | Agent * | me, | 
| Agent * | other, | ||
| double | trunc_time, | ||
| double | timestep, | ||
| double | left_pref, | ||
| double | cur_allowed_error | ||
| ) | 
| Line collvoid::createOrcaLine | ( | double | combinedRadius, | 
| const Vector2 & | relativePosition, | ||
| const Vector2 & | me_vel, | ||
| const Vector2 & | other_vel, | ||
| double | trunc_time, | ||
| double | timestep, | ||
| double | left_pref, | ||
| double | cur_allowed_error, | ||
| bool | controlled | ||
| ) | 
| VO collvoid::createRVO | ( | Vector2 & | position1, | 
| const std::vector< Vector2 > & | footprint1, | ||
| Vector2 & | vel1, | ||
| Vector2 & | position2, | ||
| const std::vector< Vector2 > & | footprint2, | ||
| Vector2 & | vel2 | ||
| ) | 
Definition at line 307 of file clearpath.cpp.
| VO collvoid::createRVO | ( | Vector2 & | position1, | 
| double | radius1, | ||
| Vector2 & | vel1, | ||
| Vector2 & | position2, | ||
| double | radius2, | ||
| Vector2 & | vel2 | ||
| ) | 
Definition at line 417 of file clearpath.cpp.
| void collvoid::createSamplesWithinMovementConstraints | ( | std::vector< VelocitySample > & | samples, | 
| double | cur_vel_x, | ||
| double | cur_vel_y, | ||
| double | cur_vel_theta, | ||
| double | acc_lim_x, | ||
| double | acc_lim_y, | ||
| double | acc_lim_theta, | ||
| double | min_vel_x, | ||
| double | max_vel_x, | ||
| double | min_vel_y, | ||
| double | max_vel_y, | ||
| double | min_vel_theta, | ||
| double | max_vel_theta, | ||
| double | heading, | ||
| Vector2 | pref_vel, | ||
| double | sim_period, | ||
| int | num_samples, | ||
| bool | holo_robot | ||
| ) | 
Definition at line 558 of file clearpath.cpp.
| Line collvoid::createStationaryAgent | ( | Agent * | me, | 
| Agent * | other | ||
| ) | 
| VO collvoid::createTruncVO | ( | VO & | vo, | 
| double | time | ||
| ) | 
Definition at line 444 of file clearpath.cpp.
| VO collvoid::createVO | ( | Vector2 & | position1, | 
| const std::vector< Vector2 > & | footprint1, | ||
| Vector2 & | position2, | ||
| const std::vector< Vector2 > & | footprint2, | ||
| Vector2 & | vel2 | ||
| ) | 
Definition at line 194 of file clearpath.cpp.
| VO collvoid::createVO | ( | Vector2 & | position1, | 
| const std::vector< Vector2 > & | footprint1, | ||
| Vector2 & | vel1, | ||
| Vector2 & | position2, | ||
| const std::vector< Vector2 > & | footprint2, | ||
| Vector2 & | vel2, | ||
| int | TYPE | ||
| ) | 
Definition at line 365 of file clearpath.cpp.
| VO collvoid::createVO | ( | Vector2 & | position1, | 
| double | radius1, | ||
| Vector2 & | vel1, | ||
| Vector2 & | position2, | ||
| double | radius2, | ||
| Vector2 & | vel2, | ||
| int | TYPE | ||
| ) | 
Definition at line 378 of file clearpath.cpp.
| VO collvoid::createVO | ( | Vector2 & | position1, | 
| double | radius1, | ||
| Vector2 & | position2, | ||
| double | radius2, | ||
| Vector2 & | vel2 | ||
| ) | 
Definition at line 391 of file clearpath.cpp.
| double collvoid::cross | ( | const ConvexHullPoint & | O, | 
| const ConvexHullPoint & | A, | ||
| const ConvexHullPoint & | B | ||
| ) | 
Definition at line 847 of file clearpath.cpp.
| double collvoid::det | ( | const Vector2 & | vector1, | 
| const Vector2 & | vector2 | ||
| ) |  [inline] | 
        
| double collvoid::distSqPointLineSegment | ( | const Vector2 & | a, | 
| const Vector2 & | b, | ||
| const Vector2 & | c | ||
| ) |  [inline] | 
        
Computes the squared distance from a line segment with the specified endpoints to a specified point.
| a | The first endpoint of the line segment. | 
| b | The second endpoint of the line segment. | 
| c | The point to which the squared distance is to be calculated. | 
| void collvoid::fillMarkerWithROSAgent | ( | visualization_msgs::MarkerArray & | marker, | 
| ROSAgent * | agent, | ||
| std::string | base_frame, | ||
| std::string | name_space | ||
| ) | 
Definition at line 265 of file collvoid_publishers.cpp.
| double collvoid::gamma | ( | double | T, | 
| double | theta, | ||
| double | error, | ||
| double | v_max_ang | ||
| ) | 
| Vector2 collvoid::intersectTwoLines | ( | Vector2 | point1, | 
| Vector2 | dir1, | ||
| Vector2 | point2, | ||
| Vector2 | dir2 | ||
| ) | 
Definition at line 887 of file clearpath.cpp.
| Vector2 collvoid::intersectTwoLines | ( | Line | line1, | 
| Line | line2 | ||
| ) | 
Definition at line 910 of file clearpath.cpp.
| bool collvoid::isInsideVO | ( | VO | vo, | 
| Vector2 | point, | ||
| bool | use_truncation | ||
| ) | 
Definition at line 472 of file clearpath.cpp.
| bool collvoid::isWithinAdditionalConstraints | ( | const std::vector< Line > & | additional_constraints, | 
| const Vector2 & | point | ||
| ) | 
Definition at line 479 of file clearpath.cpp.
| double collvoid::left | ( | const Vector2 & | pointLine, | 
| const Vector2 & | dirLine, | ||
| const Vector2 & | point | ||
| ) |  [inline] | 
        
| bool collvoid::leftOf | ( | const Vector2 & | pointLine, | 
| const Vector2 & | dirLine, | ||
| const Vector2 & | point | ||
| ) |  [inline] | 
        
| bool collvoid::linearProgram1 | ( | const std::vector< Line > & | lines, | 
| size_t | lineNo, | ||
| float | radius, | ||
| const Vector2 & | optVelocity, | ||
| bool | dirOpt, | ||
| Vector2 & | result | ||
| ) | 
| size_t collvoid::linearProgram2 | ( | const std::vector< Line > & | lines, | 
| float | radius, | ||
| const Vector2 & | optVelocity, | ||
| bool | dirOpt, | ||
| Vector2 & | result | ||
| ) | 
| void collvoid::linearProgram3 | ( | const std::vector< Line > & | lines, | 
| size_t | numObstLines, | ||
| size_t | beginLine, | ||
| float | radius, | ||
| Vector2 & | result | ||
| ) | 
| std::vector< Vector2 > collvoid::minkowskiSum | ( | const std::vector< Vector2 > | polygon1, | 
| const std::vector< Vector2 > | polygon2 | ||
| ) | 
Definition at line 821 of file clearpath.cpp.
| Vector2 collvoid::normal | ( | const Vector2 & | vector | ) |  [inline] | 
        
| Vector2 collvoid::normalize | ( | const Vector2 & | vector | ) |  [inline] | 
        
| void collvoid::odomCallback | ( | const nav_msgs::Odometry::ConstPtr & | msg | ) | 
Definition at line 230 of file helper.cpp.
| Vector2 collvoid::operator* | ( | float | s, | 
| const Vector2 & | vector | ||
| ) |  [inline] | 
        
| Vector2 collvoid::projectPointOnLine | ( | const Vector2 & | pointLine, | 
| const Vector2 & | dirLine, | ||
| const Vector2 & | point | ||
| ) |  [inline] | 
        
| void collvoid::publishHoloSpeed | ( | Vector2 | pos, | 
| Vector2 | vel, | ||
| std::string | base_frame, | ||
| std::string | name_space, | ||
| ros::Publisher | speed_pub | ||
| ) | 
Definition at line 36 of file collvoid_publishers.cpp.
| void collvoid::publishMePosition | ( | ROSAgent * | me, | 
| std::string | base_frame, | ||
| std::string | name_space, | ||
| ros::Publisher | me_pub | ||
| ) | 
Definition at line 245 of file collvoid_publishers.cpp.
| void collvoid::publishNeighborPositions | ( | std::vector< AgentPtr > & | neighbors, | 
| std::string | base_frame, | ||
| std::string | name_space, | ||
| ros::Publisher | neighbors_pub | ||
| ) | 
Definition at line 253 of file collvoid_publishers.cpp.
| void collvoid::publishObstacleLines | ( | const std::vector< Obstacle > & | obstacles_lines, | 
| std::string | base_frame, | ||
| std::string | name_space, | ||
| ros::Publisher | line_pub | ||
| ) | 
Definition at line 214 of file collvoid_publishers.cpp.
| void collvoid::publishOrcaLines | ( | const std::vector< Line > & | orca_lines, | 
| Vector2 & | position, | ||
| std::string | base_frame, | ||
| std::string | name_space, | ||
| ros::Publisher | line_pub | ||
| ) | 
Definition at line 187 of file collvoid_publishers.cpp.
| void collvoid::publishPoints | ( | Vector2 & | pos, | 
| const std::vector< VelocitySample > & | points, | ||
| std::string | base_frame, | ||
| std::string | name_space, | ||
| ros::Publisher | samples_pub | ||
| ) | 
Definition at line 135 of file collvoid_publishers.cpp.
| void collvoid::publishVOs | ( | Vector2 & | pos, | 
| const std::vector< VO > & | truncated_vos, | ||
| bool | use_truncation, | ||
| std::string | base_frame, | ||
| std::string | name_space, | ||
| ros::Publisher | vo_pub | ||
| ) | 
Definition at line 62 of file collvoid_publishers.cpp.
| bool collvoid::rightOf | ( | const Vector2 & | pointLine, | 
| const Vector2 & | dirLine, | ||
| const Vector2 & | point | ||
| ) |  [inline] | 
        
| Vector2 collvoid::rotateVectorByAngle | ( | double | x, | 
| double | y, | ||
| double | ang | ||
| ) |  [inline] | 
        
| Vector2 collvoid::rotateVectorByAngle | ( | const Vector2 & | vec, | 
| double | ang | ||
| ) |  [inline] | 
        
| double collvoid::sign | ( | double | x | ) |  [inline] | 
        
| double collvoid::signedDistPointToLineSegment | ( | const Vector2 & | a, | 
| const Vector2 & | b, | ||
| const Vector2 & | c | ||
| ) |  [inline] | 
        
Computes the sign from a line connecting the specified points to a specified point.
| a | The first point on the line. | 
| b | The second point on the line. | 
| c | The point to which the signed distance is to be calculated. | 
| double collvoid::sqr | ( | double | a | ) |  [inline] | 
        
| std::string collvoid::base_frame_ | 
Definition at line 45 of file helper.cpp.
Definition at line 47 of file helper.cpp.
| double collvoid::eps_ | 
Definition at line 50 of file helper.cpp.
| geometry_msgs::PolygonStamped collvoid::footprint_msg_ | 
Definition at line 49 of file helper.cpp.
| double collvoid::footprint_radius_ | 
Definition at line 47 of file helper.cpp.
| std::string collvoid::global_frame_ | 
Definition at line 45 of file helper.cpp.
| std::vector<Vector2> collvoid::minkowski_footprint_ | 
Definition at line 48 of file helper.cpp.
| std::string collvoid::odom_frame_ | 
Definition at line 45 of file helper.cpp.
| std::vector<std::pair<double, geometry_msgs::PoseStamped> > collvoid::pose_array_weighted_ | 
Definition at line 46 of file helper.cpp.
| double collvoid::radius_ | 
Definition at line 47 of file helper.cpp.
Definition at line 44 of file helper.cpp.