Carma-platform v4.2.0
CARMA Platform is built on robot operating system (ROS) and utilizes open source software (OSS) that enables Cooperative Driving Automation (CDA) features to allow Automated Driving Systems to interact and cooperate with infrastructure and other vehicles through communication.
collision_detection.hpp File Reference
#include <carma_perception_msgs/msg/roadway_obstacle_list.hpp>
#include <carma_perception_msgs/msg/roadway_obstacle.hpp>
#include <carma_v2x_msgs/msg/vehicle_size.hpp>
#include <carma_planning_msgs/msg/trajectory_plan.hpp>
#include <geometry_msgs/msg/vector3.hpp>
#include <boost/geometry.hpp>
#include <boost/geometry/geometries/point_xy.hpp>
#include <boost/foreach.hpp>
#include <vector>
#include <boost/assign/std/vector.hpp>
#include <iostream>
#include <fstream>
#include <carma_wm/Geometry.hpp>
#include <tf2/LinearMath/Transform.h>
#include <tf2_geometry_msgs/tf2_geometry_msgs.h>
#include <rclcpp/rclcpp.hpp>
Include dependency graph for collision_detection.hpp:
This graph shows which files directly or indirectly include this file:

Go to the source code of this file.

Classes

struct  carma_wm::collision_detection::MovingObject
 

Namespaces

namespace  carma_wm
 
namespace  carma_wm::collision_detection
 

Typedefs

typedef boost::geometry::model::point< double, 2, boost::geometry::cs::cartesian > carma_wm::collision_detection::point_t
 
typedef boost::geometry::model::polygon< point_t > carma_wm::collision_detection::polygon_t
 

Functions

std::vector< carma_perception_msgs::msg::RoadwayObstacle > carma_wm::collision_detection::WorldCollisionDetection (const carma_perception_msgs::msg::RoadwayObstacleList &rwol, const carma_planning_msgs::msg::TrajectoryPlan &tp, const geometry_msgs::msg::Vector3 &size, const geometry_msgs::msg::Twist &velocity)
 Main collision detection function to be called when needed to check for collision detection of the vehicle with the current trajectory plan and the current world objects. More...
 
collision_detection::MovingObject carma_wm::collision_detection::ConvertRoadwayObstacleToMovingObject (const carma_perception_msgs::msg::RoadwayObstacle &rwo)
 Convert RodwayObstable object to the collision_detection::MovingObject. More...
 
collision_detection::MovingObject carma_wm::collision_detection::ConvertVehicleToMovingObject (const carma_planning_msgs::msg::TrajectoryPlan &tp, const geometry_msgs::msg::Vector3 &size, const geometry_msgs::msg::Twist &veloctiy)
 Creates collision_detection::MovingObject for the host vehicle using the veloctiy, size, TrajectoryPlan. More...
 
collision_detection::MovingObject carma_wm::collision_detection::PredictObjectPosition (collision_detection::MovingObject const &op, __uint64_t target_time)
 .function is to create a monving object with a polygon that represents area that object is going to allocated until a given time by creating a convex hull around the future polygons More...
 
bool carma_wm::collision_detection::CheckPolygonIntersection (collision_detection::MovingObject const &ob_1, collision_detection::MovingObject const &ob_2)
 .check Intersection between polygons More...
 
bool carma_wm::collision_detection::DetectCollision (collision_detection::MovingObject const &ob_1, collision_detection::MovingObject const &ob_2, __uint64_t target_time)
 .function is used in WorldCollisionDetection to detection collision between two Moving Object More...
 
template<class P >
carma_wm::collision_detection::ObjectToBoostPolygon (const geometry_msgs::msg::Pose &pose, const geometry_msgs::msg::Vector3 &size)
 function to create a polygon representing and object More...