diff --git a/simulator/simple_planning_simulator/design/simple_planning_simulator-design.md b/simulator/simple_planning_simulator/design/simple_planning_simulator-design.md index 5399fe67bdf86..c12d13cb0177e 100644 --- a/simulator/simple_planning_simulator/design/simple_planning_simulator-design.md +++ b/simulator/simple_planning_simulator/design/simple_planning_simulator-design.md @@ -17,16 +17,24 @@ The purpose of this simulator is for the integration test of planning and contro ### input -- input/vehicle_control_command [`autoware_auto_msgs/msg/VehicleControlCommand`] : target command to drive a vehicle. -- input/ackermann_control_command [`autoware_auto_msgs/msg/AckermannControlCommand`] : target command to drive a vehicle. -- input/vehicle_state_command [`autoware_auto_msgs/msg/VehicleStateCommand`] : target state command (e.g. gear). - /initialpose [`geometry_msgs/msg/PoseWithCovarianceStamped`] : for initial pose +- input/ackermann_control_command [`autoware_auto_msgs/msg/AckermannControlCommand`] : target command to drive a vehicle +- input/manual_ackermann_control_command [`autoware_auto_msgs/msg/AckermannControlCommand`] : manual target command to drive a vehicle (used when control_mode_request = Manual) +- input/gear_command [`autoware_auto_vehicle_msgs/msg/GearCommand`] : target gear command. +- input/manual_gear_command [`autoware_auto_vehicle_msgs/msg/GearCommand`] : target gear command (used when control_mode_request = Manual) +- input/turn_indicators_command [`autoware_auto_vehicle_msgs/msg/TurnIndicatorsCommand`] : target turn indicator command +- input/hazard_lights_command [`autoware_auto_vehicle_msgs/msg/HazardLightsCommand`] : target hazard lights command +- input/control_mode_request [`tier4_vehicle_msgs::srv::ControlModeRequest`] : mode change for Auto/Manual driving ### output - /tf [`tf2_msgs/msg/TFMessage`] : simulated vehicle pose (base_link) -- /vehicle/vehicle_kinematic_state [`autoware_auto_msgs/msg/VehicleKinematicState`] : simulated kinematic state (defined in CoM) -- /vehicle/state_report [`autoware_auto_msgs/msg/VehicleStateReport`] : current vehicle state (e.g. gear, mode, etc.) +- /output/odometry [`nav_msgs/msg/Odometry`] : simulated vehicle pose and twist +- /output/steering [`autoware_auto_vehicle_msgs/msg/SteeringReport`] : simulated steering angle +- /output/control_mode_report [`autoware_auto_vehicle_msgs/msg/ControlModeReport`] : current control mode (Auto/Manual) +- /output/gear_report [`autoware_auto_vehicle_msgs/msg/ControlModeReport`] : simulated gear +- /output/turn_indicators_report [`autoware_auto_vehicle_msgs/msg/ControlModeReport`] : simulated turn indicator status +- /output/hazard_lights_report [`autoware_auto_vehicle_msgs/msg/ControlModeReport`] : simulated hazard lights status ## Inner-workings / Algorithms diff --git a/simulator/simple_planning_simulator/src/simple_planning_simulator/simple_planning_simulator_core.cpp b/simulator/simple_planning_simulator/src/simple_planning_simulator/simple_planning_simulator_core.cpp index 1ef3ea9d845ad..06585ec751981 100644 --- a/simulator/simple_planning_simulator/src/simple_planning_simulator/simple_planning_simulator_core.cpp +++ b/simulator/simple_planning_simulator/src/simple_planning_simulator/simple_planning_simulator_core.cpp @@ -109,7 +109,7 @@ SimplePlanningSimulator::SimplePlanningSimulator(const rclcpp::NodeOptions & opt "input/trajectory", QoS{1}, std::bind(&SimplePlanningSimulator::on_trajectory, this, _1)); srv_mode_req_ = create_service( - "control_mode_request", + "input/control_mode_request", std::bind(&SimplePlanningSimulator::on_control_mode_request, this, _1, _2)); // TODO(Horibe): will be replaced by mode_request. May still be needed for scenario testing