Skip to content

Commit

Permalink
fix(simple_planning_simulator): initialize variables
Browse files Browse the repository at this point in the history
Signed-off-by: Takamasa Horibe <[email protected]>
  • Loading branch information
TakaHoribe committed Nov 1, 2023
1 parent 17b02d3 commit 4e7cce8
Showing 1 changed file with 23 additions and 23 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -171,36 +171,36 @@ class PLANNING_SIMULATOR_PUBLIC SimplePlanningSimulator : public rclcpp::Node
tf2_ros::TransformListener tf_listener_;

/* received & published topics */
PoseWithCovarianceStamped::ConstSharedPtr initial_pose_;
TwistStamped initial_twist_;
VelocityReport current_velocity_;
Odometry current_odometry_;
SteeringReport current_steer_;
AckermannControlCommand current_ackermann_cmd_;
AckermannControlCommand current_manual_ackermann_cmd_;
GearCommand current_gear_cmd_;
GearCommand current_manual_gear_cmd_;
TurnIndicatorsCommand::ConstSharedPtr current_turn_indicators_cmd_ptr_;
HazardLightsCommand::ConstSharedPtr current_hazard_lights_cmd_ptr_;
Trajectory::ConstSharedPtr current_trajectory_ptr_;
bool simulate_motion_; //!< stop vehicle motion simulation if false
ControlModeReport current_control_mode_;
bool enable_road_slope_simulation_;
PoseWithCovarianceStamped::ConstSharedPtr initial_pose_{};
TwistStamped initial_twist_{};
VelocityReport current_velocity_{};
Odometry current_odometry_{};
SteeringReport current_steer_{};
AckermannControlCommand current_ackermann_cmd_{};
AckermannControlCommand current_manual_ackermann_cmd_{};
GearCommand current_gear_cmd_{};
GearCommand current_manual_gear_cmd_{};
TurnIndicatorsCommand::ConstSharedPtr current_turn_indicators_cmd_ptr_{};
HazardLightsCommand::ConstSharedPtr current_hazard_lights_cmd_ptr_{};
Trajectory::ConstSharedPtr current_trajectory_ptr_{};
bool simulate_motion_ = true; //!< stop vehicle motion simulation if false
ControlModeReport current_control_mode_{};
bool enable_road_slope_simulation_ = true;

/* frame_id */
std::string simulated_frame_id_; //!< @brief simulated vehicle frame id
std::string origin_frame_id_; //!< @brief map frame_id
std::string simulated_frame_id_ = ""; //!< @brief simulated vehicle frame id
std::string origin_frame_id_ = ""; //!< @brief map frame_id

/* flags */
bool is_initialized_; //!< @brief flag to check the initial position is set
bool add_measurement_noise_; //!< @brief flag to add measurement noise
bool is_initialized_ = false; //!< @brief flag to check the initial position is set
bool add_measurement_noise_ = false; //!< @brief flag to add measurement noise

DeltaTime delta_time_; //!< @brief to calculate delta time
DeltaTime delta_time_{}; //!< @brief to calculate delta time

MeasurementNoiseGenerator measurement_noise_; //!< @brief for measurement noise
MeasurementNoiseGenerator measurement_noise_{}; //!< @brief for measurement noise

double x_stddev_; //!< @brief x standard deviation for dummy covariance in map coordinate
double y_stddev_; //!< @brief y standard deviation for dummy covariance in map coordinate
double x_stddev_ = 0.0; //!< @brief x standard deviation for dummy covariance in map coordinate
double y_stddev_ = 0.0; //!< @brief y standard deviation for dummy covariance in map coordinate

/* vehicle model */
enum class VehicleModelType {
Expand Down

0 comments on commit 4e7cce8

Please sign in to comment.