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.
trajectory_visualizer.hpp
Go to the documentation of this file.
1#pragma once
2
3/*
4 * Copyright (C) 2020-2022 LEIDOS.
5 *
6 * Licensed under the Apache License, Version 2.0 (the "License"); you may not
7 * use this file except in compliance with the License. You may obtain a copy of
8 * the License at
9 *
10 * http://www.apache.org/licenses/LICENSE-2.0
11 *
12 * Unless required by applicable law or agreed to in writing, software
13 * distributed under the License is distributed on an "AS IS" BASIS, WITHOUT
14 * WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. See the
15 * License for the specific language governing permissions and limitations under
16 * the License.
17 */
18
19#include <rclcpp/rclcpp.hpp>
20#include <carma_planning_msgs/msg/trajectory_plan.hpp>
21#include <carma_ros2_utils/carma_lifecycle_node.hpp>
22#include <visualization_msgs/msg/marker_array.hpp>
24
26{
27
33 const double MPH_TO_MS = 0.44704;
34
35 class TrajectoryVisualizer : public carma_ros2_utils::CarmaLifecycleNode
36 {
37
38 private:
39 // Subscribers
40 carma_ros2_utils::SubPtr<carma_planning_msgs::msg::TrajectoryPlan> traj_sub_;
41
42 // Publishers
43 carma_ros2_utils::PubPtr<visualization_msgs::msg::MarkerArray> traj_marker_pub_;
44
45 // Node configuration
47
48 // callbacks
49 void callbackPlanTrajectory(carma_planning_msgs::msg::TrajectoryPlan::UniquePtr msg);
50
51 // variables
52 double max_speed_;
53
55 // we are not saving every trajectory history at this point
56
57 public:
58
62 explicit TrajectoryVisualizer(const rclcpp::NodeOptions &);
63
65 // Overrides
67 carma_ros2_utils::CallbackReturn handle_on_configure(const rclcpp_lifecycle::State &);
68
69 };
70}
71
72
TrajectoryVisualizer(const rclcpp::NodeOptions &)
TrajectoryVisualizer constructor.
carma_ros2_utils::CallbackReturn handle_on_configure(const rclcpp_lifecycle::State &)
void callbackPlanTrajectory(carma_planning_msgs::msg::TrajectoryPlan::UniquePtr msg)
carma_ros2_utils::PubPtr< visualization_msgs::msg::MarkerArray > traj_marker_pub_
carma_ros2_utils::SubPtr< carma_planning_msgs::msg::TrajectoryPlan > traj_sub_
max_speed values for trajectory_visualizer