#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>
Go to the source code of this file.
◆ 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
Macro definition to enable easier access to fields shared across the maneuver types.
- Parameters
-
mvr | The maneuver object to invoke the accessors on |
property | The 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.