Skip to content
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
Original file line number Diff line number Diff line change
Expand Up @@ -18,7 +18,6 @@
#include "autoware/simple_planning_simulator/vehicle_model/sim_model_interface.hpp"
#include "autoware/simple_planning_simulator/visibility_control.hpp"
#include "rclcpp/rclcpp.hpp"
#include "tier4_api_utils/tier4_api_utils.hpp"

#include "autoware_control_msgs/msg/control.hpp"
#include "autoware_map_msgs/msg/lanelet_map_bin.hpp"
Expand All @@ -43,7 +42,6 @@
#include "geometry_msgs/msg/twist_stamped.hpp"
#include "nav_msgs/msg/odometry.hpp"
#include "sensor_msgs/msg/imu.hpp"
#include "tier4_external_api_msgs/srv/initialize_pose.hpp"
#include "tier4_vehicle_msgs/msg/actuation_command_stamped.hpp"
#include "tier4_vehicle_msgs/msg/actuation_status_stamped.hpp"

Expand Down Expand Up @@ -83,7 +81,6 @@ using geometry_msgs::msg::Twist;
using geometry_msgs::msg::TwistStamped;
using nav_msgs::msg::Odometry;
using sensor_msgs::msg::Imu;
using tier4_external_api_msgs::srv::InitializePose;
using tier4_vehicle_msgs::msg::ActuationCommandStamped;
using tier4_vehicle_msgs::msg::ActuationStatusStamped;

Expand Down Expand Up @@ -158,7 +155,6 @@ class PLANNING_SIMULATOR_PUBLIC SimplePlanningSimulator : public rclcpp::Node
rclcpp::Service<ControlModeCommand>::SharedPtr srv_mode_req_;

rclcpp::CallbackGroup::SharedPtr group_api_service_;
tier4_api_utils::Service<InitializePose>::SharedPtr srv_set_pose_;

uint32_t timer_sampling_time_ms_; //!< @brief timer sampling time
rclcpp::TimerBase::SharedPtr on_timer_; //!< @brief timer for simulation
Expand Down Expand Up @@ -263,13 +259,6 @@ class PLANNING_SIMULATOR_PUBLIC SimplePlanningSimulator : public rclcpp::Node
*/
void on_initialtwist(const TwistStamped::ConstSharedPtr msg);

/**
* @brief set initial pose for simulation with received request
*/
void on_set_pose(
const InitializePose::Request::ConstSharedPtr request,
const InitializePose::Response::SharedPtr response);

/**
* @brief subscribe trajectory for deciding self z position.
*/
Expand Down
2 changes: 0 additions & 2 deletions simulator/autoware_simple_planning_simulator/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -37,8 +37,6 @@
<depend>tf2</depend>
<depend>tf2_geometry_msgs</depend>
<depend>tf2_ros</depend>
<depend>tier4_api_utils</depend>
<depend>tier4_external_api_msgs</depend>
<depend>tier4_vehicle_msgs</depend>
<build_depend>autoware_cmake</build_depend>

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -184,13 +184,7 @@
on_timer_ = rclcpp::create_timer(
this, get_clock(), std::chrono::milliseconds(timer_sampling_time_ms_),
std::bind(&SimplePlanningSimulator::on_timer, this));

Check notice on line 187 in simulator/autoware_simple_planning_simulator/src/simple_planning_simulator/simple_planning_simulator_core.cpp

View check run for this annotation

CodeScene Delta Analysis / CodeScene Code Health Review (main)

✅ Getting better: Large Method

SimplePlanningSimulator::SimplePlanningSimulator decreases from 109 to 104 lines of code, threshold = 70. Large functions with many lines of code are generally harder to understand and lower the code health. Avoid adding more lines to this function.
tier4_api_utils::ServiceProxyNodeInterface proxy(this);
group_api_service_ = create_callback_group(rclcpp::CallbackGroupType::MutuallyExclusive);
srv_set_pose_ = proxy.create_service<tier4_external_api_msgs::srv::InitializePose>(
"/api/simulator/set/pose", std::bind(&SimplePlanningSimulator::on_set_pose, this, _1, _2),
rmw_qos_profile_services_default, group_api_service_);

// set vehicle model type
initialize_vehicle_model(vehicle_model_type_str);

Expand Down Expand Up @@ -567,19 +561,6 @@
initial_twist_ = *msg;
}

void SimplePlanningSimulator::on_set_pose(
const InitializePose::Request::ConstSharedPtr request,
const InitializePose::Response::SharedPtr response)
{
// save initial pose
Twist initial_twist;
PoseStamped initial_pose;
initial_pose.header = request->pose.header;
initial_pose.pose = request->pose.pose.pose;
set_initial_state_with_transform(initial_pose, initial_twist);
response->status = tier4_api_utils::response_success();
}

void SimplePlanningSimulator::set_input(const InputCommand & cmd, const double acc_by_slope)
{
std::visit(
Expand Down
Loading