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.
stop_controlled_intersection_plugin.hpp File Reference
#include <vector>
#include <carma_planning_msgs/msg/trajectory_plan.hpp>
#include <carma_planning_msgs/msg/trajectory_plan_point.hpp>
#include <carma_planning_msgs/msg/plugin.hpp>
#include <carma_guidance_plugins/tactical_plugin.hpp>
#include <boost/shared_ptr.hpp>
#include <boost/geometry.hpp>
#include <carma_ros2_utils/carma_lifecycle_node.hpp>
#include <carma_wm/Geometry.hpp>
#include <carma_planning_msgs/srv/plan_trajectory.hpp>
#include <carma_wm/WMListener.hpp>
#include <functional>
#include "stop_controlled_intersection_config.hpp"
#include <unordered_set>
#include <autoware_msgs/msg/lane.hpp>
#include <rclcpp/rclcpp.hpp>
#include <carma_planning_msgs/msg/maneuver.hpp>
#include <basic_autonomy/basic_autonomy.hpp>
#include <basic_autonomy/helper_functions.hpp>
#include <basic_autonomy/log/log.hpp>
#include <gtest/gtest_prod.h>
Include dependency graph for stop_controlled_intersection_plugin.hpp:
This graph shows which files directly or indirectly include this file:

Go to the source code of this file.

Classes

class  stop_controlled_intersection_tactical_plugin::StopControlledIntersectionTacticalPlugin
 Class containing primary business logic for the Stop Controlled Intersection Tactical Plugin. More...
 

Namespaces

namespace  stop_controlled_intersection_tactical_plugin
 

Macros

#define GET_MANEUVER_PROPERTY(mvr, property)
 Macro definition to enable easier access to fields shared across the maneuver types. More...
 

Typedefs

using stop_controlled_intersection_tactical_plugin::PointSpeedPair = basic_autonomy::waypoint_generation::PointSpeedPair
 

Macro Definition Documentation

◆ GET_MANEUVER_PROPERTY

#define GET_MANEUVER_PROPERTY (   mvr,
  property 
)
Value:
(((mvr).type == carma_planning_msgs::msg::Maneuver::INTERSECTION_TRANSIT_LEFT_TURN ? (mvr).intersection_transit_left_turn_maneuver.property :\
((mvr).type == carma_planning_msgs::msg::Maneuver::INTERSECTION_TRANSIT_RIGHT_TURN ? (mvr).intersection_transit_right_turn_maneuver.property :\
((mvr).type == carma_planning_msgs::msg::Maneuver::INTERSECTION_TRANSIT_STRAIGHT ? (mvr).intersection_transit_straight_maneuver.property :\
((mvr).type == carma_planning_msgs::msg::Maneuver::LANE_FOLLOWING ? (mvr).lane_following_maneuver.property :\
throw std::invalid_argument("GET_MANEUVER_PROPERTY (property) called on maneuver with invalid type id " + std::to_string((mvr).type)))))))
auto to_string(const UtmZone &zone) -> std::string
Definition: utm_zone.cpp:21

Macro definition to enable easier access to fields shared across the maneuver types.

Parameters
mvrThe maneuver object to invoke the accessors on
propertyThe name of the field to access on the specific maneuver types. Must be shared by all extant maneuver types
Returns
Expands to an expression (in the form of chained ternary operators) that evalutes to the desired field

Definition at line 47 of file stop_controlled_intersection_plugin.hpp.