Skip to content

Commit

Permalink
feat: apply autoware_ prefix for simple_planning_simulator (#9995)
Browse files Browse the repository at this point in the history
* feat(simple_planning_simulator): apply `autoware_` prefix (see below):

  Note:
    * In this commit, I did not organize a folder structure.
      The folder structure will be organized in the next some commits.
    * The changes will follow the Autoware's guideline as below:
        - https://autowarefoundation.github.io/autoware-documentation/main/contributing/coding-guidelines/ros-nodes/directory-structure/#package-folder

Signed-off-by: Junya Sasaki <[email protected]>

* rename(simple_planning_simulator): move headers under `include/autoware`:

  * Fixes due to this changes for .hpp/.cpp files will be applied in the next commit

Signed-off-by: Junya Sasaki <[email protected]>

* fix(simple_planning_simulator): fix include header paths

  * To follow the previous commit

Signed-off-by: Junya Sasaki <[email protected]>

* rename: `simple_planning_simulator` => `autoware_simple_planning_simulator`

Signed-off-by: Junya Sasaki <[email protected]>

* bug(autoware_simple_planning_simulator): fix missing changes

Signed-off-by: Junya Sasaki <[email protected]>

* style(pre-commit): autofix

* bug(autoware_simple_planning_simulator): fix errors in build and tests

  * I had to run after `rm -rf install build`, ... sorry

Signed-off-by: Junya Sasaki <[email protected]>

* style(pre-commit): autofix

* Fixed NOLINT

Signed-off-by: Shintaro Sakoda <[email protected]>

* Added NOLINT

Signed-off-by: Shintaro Sakoda <[email protected]>

* Fixed to autoware_simple_planning_simulator

Signed-off-by: Shintaro Sakoda <[email protected]>

---------

Signed-off-by: Junya Sasaki <[email protected]>
Signed-off-by: Shintaro Sakoda <[email protected]>
Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com>
Co-authored-by: Shintaro Sakoda <[email protected]>
  • Loading branch information
3 people authored Jan 23, 2025
1 parent cacab80 commit 1a1a18a
Show file tree
Hide file tree
Showing 56 changed files with 297 additions and 181 deletions.
2 changes: 1 addition & 1 deletion .github/CODEOWNERS
Original file line number Diff line number Diff line change
Expand Up @@ -204,7 +204,7 @@ simulator/autoware_carla_interface/** [email protected] mradityagio@gmail.
simulator/dummy_perception_publisher/** [email protected]
simulator/fault_injection/** [email protected]
simulator/learning_based_vehicle_model/** [email protected] [email protected]
simulator/simple_planning_simulator/** [email protected] [email protected] [email protected] [email protected] [email protected] [email protected] [email protected]
simulator/autoware_simple_planning_simulator/** [email protected] [email protected] [email protected] [email protected] [email protected] [email protected] kotaro.yoshimoto@tier4.jp junya.sasaki@tier4.jp
simulator/tier4_dummy_object_rviz_plugin/** [email protected]
simulator/autoware_vehicle_door_simulator/** [email protected] [email protected]
system/autoware_component_monitor/** [email protected] [email protected] [email protected]
Expand Down
2 changes: 1 addition & 1 deletion launch/tier4_simulator_launch/launch/simulator.launch.xml
Original file line number Diff line number Diff line change
Expand Up @@ -219,7 +219,7 @@
<!-- 'pose_only' mode publishes the pose topic as an alternative to ndt_localizer. 'full_motion' mode publishes the odometry and acceleration topics as an alternative to localization modules. -->
<let name="motion_publish_mode" value="pose_only" if="$(eval '&quot;$(var localization_sim_mode)&quot;==&quot;pose_twist_estimator&quot;')"/>
<let name="motion_publish_mode" value="full_motion" unless="$(eval '&quot;$(var localization_sim_mode)&quot;==&quot;pose_twist_estimator&quot;')"/>
<include file="$(find-pkg-share simple_planning_simulator)/launch/simple_planning_simulator.launch.py">
<include file="$(find-pkg-share autoware_simple_planning_simulator)/launch/simple_planning_simulator.launch.py">
<arg name="vehicle_info_param_file" value="$(var vehicle_info_param_file)"/>
<arg name="simulator_model_param_file" value="$(var simulator_model)"/>
<arg name="initial_engage_state" value="$(var initial_engage_state)"/>
Expand Down
2 changes: 1 addition & 1 deletion launch/tier4_simulator_launch/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -15,8 +15,8 @@
<buildtool_depend>autoware_cmake</buildtool_depend>

<exec_depend>autoware_fault_injection</exec_depend>
<exec_depend>autoware_simple_planning_simulator</exec_depend>
<exec_depend>dummy_perception_publisher</exec_depend>
<exec_depend>simple_planning_simulator</exec_depend>

<test_depend>ament_lint_auto</test_depend>
<test_depend>autoware_lint_common</test_depend>
Expand Down
Original file line number Diff line number Diff line change
@@ -1,5 +1,5 @@
cmake_minimum_required(VERSION 3.14)
project(simple_planning_simulator)
project(autoware_simple_planning_simulator)

find_package(autoware_cmake REQUIRED)
find_package(Python3 COMPONENTS Interpreter Development)
Expand All @@ -8,8 +8,8 @@ autoware_package()

# Component
ament_auto_add_library(${PROJECT_NAME} SHARED
include/simple_planning_simulator/simple_planning_simulator_core.hpp
include/simple_planning_simulator/visibility_control.hpp
include/autoware/simple_planning_simulator/simple_planning_simulator_core.hpp
include/autoware/simple_planning_simulator/visibility_control.hpp
src/simple_planning_simulator/simple_planning_simulator_core.cpp
src/simple_planning_simulator/vehicle_model/sim_model_interface.cpp
src/simple_planning_simulator/vehicle_model/sim_model_ideal_steer_vel.cpp
Expand All @@ -28,8 +28,8 @@ ament_auto_add_library(${PROJECT_NAME} SHARED
target_include_directories(${PROJECT_NAME} PUBLIC ${Python3_INCLUDE_DIRS} ${learning_based_vehicle_model_INCLUDE_DIRS})
# Node executable
rclcpp_components_register_node(${PROJECT_NAME}
PLUGIN "simulation::simple_planning_simulator::SimplePlanningSimulator"
EXECUTABLE ${PROJECT_NAME}_exe
PLUGIN "autoware::simulator::simple_planning_simulator::SimplePlanningSimulator"
EXECUTABLE ${PROJECT_NAME}_node
)

if(BUILD_TESTING)
Expand Down
Original file line number Diff line number Diff line change
@@ -1,4 +1,4 @@
# simple_planning_simulator
# autoware_simple_planning_simulator

## Purpose / Use cases

Expand Down
Original file line number Diff line number Diff line change
@@ -1,4 +1,4 @@
// Copyright 2021 The Autoware Foundation.
// Copyright 2025 The Autoware Foundation.
//
// Licensed under the Apache License, Version 2.0 (the "License");
// you may not use this file except in compliance with the License.
Expand All @@ -12,12 +12,12 @@
// See the License for the specific language governing permissions and
// limitations under the License.

#ifndef SIMPLE_PLANNING_SIMULATOR__SIMPLE_PLANNING_SIMULATOR_CORE_HPP_
#define SIMPLE_PLANNING_SIMULATOR__SIMPLE_PLANNING_SIMULATOR_CORE_HPP_
#ifndef AUTOWARE__SIMPLE_PLANNING_SIMULATOR__SIMPLE_PLANNING_SIMULATOR_CORE_HPP_
#define AUTOWARE__SIMPLE_PLANNING_SIMULATOR__SIMPLE_PLANNING_SIMULATOR_CORE_HPP_

#include "autoware/simple_planning_simulator/vehicle_model/sim_model_interface.hpp"
#include "autoware/simple_planning_simulator/visibility_control.hpp"
#include "rclcpp/rclcpp.hpp"
#include "simple_planning_simulator/vehicle_model/sim_model_interface.hpp"
#include "simple_planning_simulator/visibility_control.hpp"
#include "tier4_api_utils/tier4_api_utils.hpp"

#include "autoware_control_msgs/msg/control.hpp"
Expand Down Expand Up @@ -57,9 +57,7 @@
#include <variant>
#include <vector>

namespace simulation
{
namespace simple_planning_simulator
namespace autoware::simulator::simple_planning_simulator
{

using autoware_control_msgs::msg::Control;
Expand Down Expand Up @@ -406,7 +404,6 @@ class PLANNING_SIMULATOR_PUBLIC SimplePlanningSimulator : public rclcpp::Node
*/
void publish_tf(const Odometry & odometry);
};
} // namespace simple_planning_simulator
} // namespace simulation
} // namespace autoware::simulator::simple_planning_simulator

#endif // SIMPLE_PLANNING_SIMULATOR__SIMPLE_PLANNING_SIMULATOR_CORE_HPP_
#endif // AUTOWARE__SIMPLE_PLANNING_SIMULATOR__SIMPLE_PLANNING_SIMULATOR_CORE_HPP_
Original file line number Diff line number Diff line change
@@ -1,4 +1,4 @@
// Copyright 2023 Autoware Foundation
// Copyright 2025 Autoware Foundation
//
// Licensed under the Apache License, Version 2.0 (the "License");
// you may not use this file except in compliance with the License.
Expand All @@ -12,15 +12,18 @@
// See the License for the specific language governing permissions and
// limitations under the License.

#ifndef SIMPLE_PLANNING_SIMULATOR__UTILS__CSV_LOADER_HPP_
#define SIMPLE_PLANNING_SIMULATOR__UTILS__CSV_LOADER_HPP_
#ifndef AUTOWARE__SIMPLE_PLANNING_SIMULATOR__UTILS__CSV_LOADER_HPP_
#define AUTOWARE__SIMPLE_PLANNING_SIMULATOR__UTILS__CSV_LOADER_HPP_

#include <fstream>
#include <iostream>
#include <sstream>
#include <string>
#include <vector>

namespace autoware::simulator::simple_planning_simulator
{

using Table = std::vector<std::vector<std::string>>;
using Map = std::vector<std::vector<double>>;
class CSVLoader
Expand All @@ -40,4 +43,6 @@ class CSVLoader
std::string csv_path_;
};

#endif // SIMPLE_PLANNING_SIMULATOR__UTILS__CSV_LOADER_HPP_
} // namespace autoware::simulator::simple_planning_simulator

#endif // AUTOWARE__SIMPLE_PLANNING_SIMULATOR__UTILS__CSV_LOADER_HPP_
Original file line number Diff line number Diff line change
@@ -1,4 +1,4 @@
// Copyright 2024 The Autoware Foundation.
// Copyright 2025 The Autoware Foundation.
//
// Licensed under the Apache License, Version 2.0 (the "License");
// you may not use this file except in compliance with the License.
Expand All @@ -12,16 +12,16 @@
// See the License for the specific language governing permissions and
// limitations under the License.

#ifndef SIMPLE_PLANNING_SIMULATOR__UTILS__MECHANICAL_CONTROLLER_HPP_
#define SIMPLE_PLANNING_SIMULATOR__UTILS__MECHANICAL_CONTROLLER_HPP_
#ifndef AUTOWARE__SIMPLE_PLANNING_SIMULATOR__UTILS__MECHANICAL_CONTROLLER_HPP_
#define AUTOWARE__SIMPLE_PLANNING_SIMULATOR__UTILS__MECHANICAL_CONTROLLER_HPP_

#include <deque>
#include <map>
#include <optional>
#include <string>
#include <utility>

namespace autoware::simple_planning_simulator::utils::mechanical_controller
namespace autoware::simulator::simple_planning_simulator
{

using DelayBuffer = std::deque<std::pair<double, double>>;
Expand Down Expand Up @@ -203,6 +203,6 @@ class MechanicalController
const SteeringDynamics & dynamics) const;
};

} // namespace autoware::simple_planning_simulator::utils::mechanical_controller
} // namespace autoware::simulator::simple_planning_simulator

#endif // SIMPLE_PLANNING_SIMULATOR__UTILS__MECHANICAL_CONTROLLER_HPP_
#endif // AUTOWARE__SIMPLE_PLANNING_SIMULATOR__UTILS__MECHANICAL_CONTROLLER_HPP_
Original file line number Diff line number Diff line change
@@ -0,0 +1,30 @@
// Copyright 2025 The Autoware Foundation.
//
// Licensed under the Apache License, Version 2.0 (the "License");
// you may not use this file except in compliance with the License.
// You may obtain a copy of the License at
//
// http://www.apache.org/licenses/LICENSE-2.0
//
// Unless required by applicable law or agreed to in writing, software
// distributed under the License is distributed on an "AS IS" BASIS,
// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
// See the License for the specific language governing permissions and
// limitations under the License.

#ifndef AUTOWARE__SIMPLE_PLANNING_SIMULATOR__VEHICLE_MODEL__SIM_MODEL_HPP_
#define AUTOWARE__SIMPLE_PLANNING_SIMULATOR__VEHICLE_MODEL__SIM_MODEL_HPP_

#include "autoware/simple_planning_simulator/vehicle_model/sim_model_actuation_cmd.hpp"
#include "autoware/simple_planning_simulator/vehicle_model/sim_model_delay_steer_acc.hpp"
#include "autoware/simple_planning_simulator/vehicle_model/sim_model_delay_steer_acc_geared.hpp"
#include "autoware/simple_planning_simulator/vehicle_model/sim_model_delay_steer_acc_geared_wo_fall_guard.hpp"
#include "autoware/simple_planning_simulator/vehicle_model/sim_model_delay_steer_map_acc_geared.hpp"
#include "autoware/simple_planning_simulator/vehicle_model/sim_model_delay_steer_vel.hpp"
#include "autoware/simple_planning_simulator/vehicle_model/sim_model_ideal_steer_acc.hpp"
#include "autoware/simple_planning_simulator/vehicle_model/sim_model_ideal_steer_acc_geared.hpp"
#include "autoware/simple_planning_simulator/vehicle_model/sim_model_ideal_steer_vel.hpp"
#include "autoware/simple_planning_simulator/vehicle_model/sim_model_interface.hpp"
#include "autoware/simple_planning_simulator/vehicle_model/sim_model_learned_steer_vel.hpp"

#endif // AUTOWARE__SIMPLE_PLANNING_SIMULATOR__VEHICLE_MODEL__SIM_MODEL_HPP_
Original file line number Diff line number Diff line change
@@ -1,4 +1,4 @@
// Copyright 2024 The Autoware Foundation.
// Copyright 2025 The Autoware Foundation.
//
// Licensed under the Apache License, Version 2.0 (the "License");
// you may not use this file except in compliance with the License.
Expand All @@ -12,15 +12,15 @@
// See the License for the specific language governing permissions and
// limitations under the License.

#ifndef SIMPLE_PLANNING_SIMULATOR__VEHICLE_MODEL__SIM_MODEL_ACTUATION_CMD_HPP_
#define SIMPLE_PLANNING_SIMULATOR__VEHICLE_MODEL__SIM_MODEL_ACTUATION_CMD_HPP_
#ifndef AUTOWARE__SIMPLE_PLANNING_SIMULATOR__VEHICLE_MODEL__SIM_MODEL_ACTUATION_CMD_HPP_
#define AUTOWARE__SIMPLE_PLANNING_SIMULATOR__VEHICLE_MODEL__SIM_MODEL_ACTUATION_CMD_HPP_

#include "autoware/interpolation/linear_interpolation.hpp"
#include "autoware/simple_planning_simulator/utils/csv_loader.hpp"
#include "autoware/simple_planning_simulator/utils/mechanical_controller.hpp"
#include "autoware/simple_planning_simulator/vehicle_model/sim_model_interface.hpp"
#include "eigen3/Eigen/Core"
#include "eigen3/Eigen/LU"
#include "simple_planning_simulator/utils/csv_loader.hpp"
#include "simple_planning_simulator/utils/mechanical_controller.hpp"
#include "simple_planning_simulator/vehicle_model/sim_model_interface.hpp"

#include <deque>
#include <iostream>
Expand All @@ -30,8 +30,11 @@
#include <string>
#include <vector>

using autoware::simple_planning_simulator::utils::mechanical_controller::MechanicalController;
using autoware::simple_planning_simulator::utils::mechanical_controller::MechanicalParams;
namespace autoware::simulator::simple_planning_simulator
{

using autoware::simulator::simple_planning_simulator::MechanicalController;
using autoware::simulator::simple_planning_simulator::MechanicalParams;

/**
* @class ActuationMap
Expand Down Expand Up @@ -397,4 +400,6 @@ class SimModelActuationCmdMechanical : public SimModelActuationCmdVGR
double prev_steer_tire_des_{0.0}; //
};

#endif // SIMPLE_PLANNING_SIMULATOR__VEHICLE_MODEL__SIM_MODEL_ACTUATION_CMD_HPP_
} // namespace autoware::simulator::simple_planning_simulator

#endif // AUTOWARE__SIMPLE_PLANNING_SIMULATOR__VEHICLE_MODEL__SIM_MODEL_ACTUATION_CMD_HPP_
Original file line number Diff line number Diff line change
@@ -1,4 +1,4 @@
// Copyright 2021 The Autoware Foundation.
// Copyright 2025 The Autoware Foundation.
//
// Licensed under the Apache License, Version 2.0 (the "License");
// you may not use this file except in compliance with the License.
Expand All @@ -12,10 +12,10 @@
// See the License for the specific language governing permissions and
// limitations under the License.

#ifndef SIMPLE_PLANNING_SIMULATOR__VEHICLE_MODEL__SIM_MODEL_DELAY_STEER_ACC_HPP_
#define SIMPLE_PLANNING_SIMULATOR__VEHICLE_MODEL__SIM_MODEL_DELAY_STEER_ACC_HPP_
#ifndef AUTOWARE__SIMPLE_PLANNING_SIMULATOR__VEHICLE_MODEL__SIM_MODEL_DELAY_STEER_ACC_HPP_
#define AUTOWARE__SIMPLE_PLANNING_SIMULATOR__VEHICLE_MODEL__SIM_MODEL_DELAY_STEER_ACC_HPP_

#include "simple_planning_simulator/vehicle_model/sim_model_interface.hpp"
#include "autoware/simple_planning_simulator/vehicle_model/sim_model_interface.hpp"

#include <Eigen/Core>
#include <Eigen/LU>
Expand All @@ -24,6 +24,9 @@
#include <iostream>
#include <queue>

namespace autoware::simulator::simple_planning_simulator
{

class SimModelDelaySteerAcc : public SimModelInterface
{
public:
Expand Down Expand Up @@ -149,4 +152,6 @@ class SimModelDelaySteerAcc : public SimModelInterface
Eigen::VectorXd calcModel(const Eigen::VectorXd & state, const Eigen::VectorXd & input) override;
};

#endif // SIMPLE_PLANNING_SIMULATOR__VEHICLE_MODEL__SIM_MODEL_DELAY_STEER_ACC_HPP_
} // namespace autoware::simulator::simple_planning_simulator

#endif // AUTOWARE__SIMPLE_PLANNING_SIMULATOR__VEHICLE_MODEL__SIM_MODEL_DELAY_STEER_ACC_HPP_
Original file line number Diff line number Diff line change
@@ -1,4 +1,4 @@
// Copyright 2021 The Autoware Foundation.
// Copyright 2025 The Autoware Foundation.
//
// Licensed under the Apache License, Version 2.0 (the "License");
// you may not use this file except in compliance with the License.
Expand All @@ -12,10 +12,10 @@
// See the License for the specific language governing permissions and
// limitations under the License.

#ifndef SIMPLE_PLANNING_SIMULATOR__VEHICLE_MODEL__SIM_MODEL_DELAY_STEER_ACC_GEARED_HPP_
#define SIMPLE_PLANNING_SIMULATOR__VEHICLE_MODEL__SIM_MODEL_DELAY_STEER_ACC_GEARED_HPP_
#ifndef AUTOWARE__SIMPLE_PLANNING_SIMULATOR__VEHICLE_MODEL__SIM_MODEL_DELAY_STEER_ACC_GEARED_HPP_ // NOLINT
#define AUTOWARE__SIMPLE_PLANNING_SIMULATOR__VEHICLE_MODEL__SIM_MODEL_DELAY_STEER_ACC_GEARED_HPP_ // NOLINT

#include "simple_planning_simulator/vehicle_model/sim_model_interface.hpp"
#include "autoware/simple_planning_simulator/vehicle_model/sim_model_interface.hpp"

#include <Eigen/Core>
#include <Eigen/LU>
Expand All @@ -24,6 +24,9 @@
#include <iostream>
#include <queue>

namespace autoware::simulator::simple_planning_simulator
{

class SimModelDelaySteerAccGeared : public SimModelInterface
{
public:
Expand Down Expand Up @@ -160,4 +163,7 @@ class SimModelDelaySteerAccGeared : public SimModelInterface
const double dt);
};

#endif // SIMPLE_PLANNING_SIMULATOR__VEHICLE_MODEL__SIM_MODEL_DELAY_STEER_ACC_GEARED_HPP_
} // namespace autoware::simulator::simple_planning_simulator

// NOLINTNEXTLINE
#endif // AUTOWARE__SIMPLE_PLANNING_SIMULATOR__VEHICLE_MODEL__SIM_MODEL_DELAY_STEER_ACC_GEARED_HPP_
Original file line number Diff line number Diff line change
@@ -1,4 +1,4 @@
// Copyright 2024 The Autoware Foundation.
// Copyright 2025 The Autoware Foundation.
//
// Licensed under the Apache License, Version 2.0 (the "License");
// you may not use this file except in compliance with the License.
Expand All @@ -12,10 +12,10 @@
// See the License for the specific language governing permissions and
// limitations under the License.

#ifndef SIMPLE_PLANNING_SIMULATOR__VEHICLE_MODEL__SIM_MODEL_DELAY_STEER_ACC_GEARED_WO_FALL_GUARD_HPP_ // NOLINT
#define SIMPLE_PLANNING_SIMULATOR__VEHICLE_MODEL__SIM_MODEL_DELAY_STEER_ACC_GEARED_WO_FALL_GUARD_HPP_ // NOLINT
#ifndef AUTOWARE__SIMPLE_PLANNING_SIMULATOR__VEHICLE_MODEL__SIM_MODEL_DELAY_STEER_ACC_GEARED_WO_FALL_GUARD_HPP_ // NOLINT
#define AUTOWARE__SIMPLE_PLANNING_SIMULATOR__VEHICLE_MODEL__SIM_MODEL_DELAY_STEER_ACC_GEARED_WO_FALL_GUARD_HPP_ // NOLINT

#include "simple_planning_simulator/vehicle_model/sim_model_interface.hpp"
#include "autoware/simple_planning_simulator/vehicle_model/sim_model_interface.hpp"

#include <Eigen/Core>
#include <Eigen/LU>
Expand All @@ -24,6 +24,9 @@
#include <iostream>
#include <queue>

namespace autoware::simulator::simple_planning_simulator
{

class SimModelDelaySteerAccGearedWoFallGuard : public SimModelInterface
{
public:
Expand Down Expand Up @@ -145,6 +148,7 @@ class SimModelDelaySteerAccGearedWoFallGuard : public SimModelInterface
Eigen::VectorXd calcModel(const Eigen::VectorXd & state, const Eigen::VectorXd & input) override;
};

// clang-format off
#endif // SIMPLE_PLANNING_SIMULATOR__VEHICLE_MODEL__SIM_MODEL_DELAY_STEER_ACC_GEARED_WO_FALL_GUARD_HPP_ // NOLINT
// clang-format on
} // namespace autoware::simulator::simple_planning_simulator

// NOLINTNEXTLINE
#endif // AUTOWARE__SIMPLE_PLANNING_SIMULATOR__VEHICLE_MODEL__SIM_MODEL_DELAY_STEER_ACC_GEARED_WO_FALL_GUARD_HPP_
Loading

0 comments on commit 1a1a18a

Please sign in to comment.