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.
arbitrator_utils.hpp File Reference
#include <rclcpp/rclcpp.hpp>
#include <carma_planning_msgs/msg/maneuver_plan.hpp>
Include dependency graph for arbitrator_utils.hpp:
This graph shows which files directly or indirectly include this file:

Go to the source code of this file.

Namespaces

namespace  arbitrator_utils
 

Macros

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

Functions

rclcpp::Time arbitrator_utils::get_plan_start_time (const carma_planning_msgs::msg::ManeuverPlan &)
 Get the start time of the first maneuver in the plan. More...
 
double arbitrator_utils::get_plan_start_distance (const carma_planning_msgs::msg::ManeuverPlan &)
 Get the start distance of the first maneuver in the plan. More...
 
rclcpp::Time arbitrator_utils::get_plan_end_time (const carma_planning_msgs::msg::ManeuverPlan &)
 Get the end time of the first maneuver in the plan. More...
 
double arbitrator_utils::get_plan_end_distance (const carma_planning_msgs::msg::ManeuverPlan &)
 Get the end distance of the first maneuver in the plan. More...
 
rclcpp::Time arbitrator_utils::get_maneuver_start_time (const carma_planning_msgs::msg::Maneuver &)
 Get the start time of the specified maneuver. More...
 
double arbitrator_utils::get_maneuver_start_distance (const carma_planning_msgs::msg::Maneuver &)
 Get the start distance the specified maneuver. More...
 
rclcpp::Time arbitrator_utils::get_maneuver_end_time (const carma_planning_msgs::msg::Maneuver &)
 Get the end time of the specified maneuver. More...
 
double arbitrator_utils::get_maneuver_end_distance (const carma_planning_msgs::msg::Maneuver &)
 Get the end distance of the specified maneuver. More...
 

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_CHANGE ? (mvr).lane_change_maneuver.property :\
((mvr).type == carma_planning_msgs::msg::Maneuver::LANE_FOLLOWING ? (mvr).lane_following_maneuver.property :\
((mvr).type == carma_planning_msgs::msg::Maneuver::STOP_AND_WAIT ? (mvr).stop_and_wait_maneuver.property :\
throw std::invalid_argument("GET_MANEUVER_PROPERTY (property) called on maneuver with invalid type id"))))))))

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

TODO: Implement a better system for handling Maneuver objects such that this macro isn't needed.

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 33 of file arbitrator_utils.hpp.