diff --git a/irobot_create_common/irobot_create_nodes/src/kidnap_estimator_publisher.cpp b/irobot_create_common/irobot_create_nodes/src/kidnap_estimator_publisher.cpp index 9f1deab1..c08ed4e1 100644 --- a/irobot_create_common/irobot_create_nodes/src/kidnap_estimator_publisher.cpp +++ b/irobot_create_common/irobot_create_nodes/src/kidnap_estimator_publisher.cpp @@ -43,15 +43,15 @@ void KidnapEstimator::kidnap_callback(irobot_create_msgs::msg::HazardDetectionVe const std::size_t wheel_drop_count = std::count_if( hazard_vector.begin(), hazard_vector.end(), [](auto hazard_vector) { return hazard_vector.header.frame_id == "wheel_drop_left" || - hazard_vector.header.frame_id == "wheel_drop_right"; + hazard_vector.header.frame_id == "wheel_drop_right"; }); const std::size_t cliff_sensor_count = std::count_if( hazard_vector.begin(), hazard_vector.end(), [](auto hazard_vector) { return hazard_vector.header.frame_id == "cliff_side_left" || - hazard_vector.header.frame_id == "cliff_side_right" || - hazard_vector.header.frame_id == "cliff_front_left" || - hazard_vector.header.frame_id == "cliff_front_right"; + hazard_vector.header.frame_id == "cliff_side_right" || + hazard_vector.header.frame_id == "cliff_front_left" || + hazard_vector.header.frame_id == "cliff_front_right"; }); // Set header timestamp. diff --git a/irobot_create_common/irobot_create_nodes/src/motion_control/wall_follow_states.cpp b/irobot_create_common/irobot_create_nodes/src/motion_control/wall_follow_states.cpp index f16b1261..02b55ab5 100644 --- a/irobot_create_common/irobot_create_nodes/src/motion_control/wall_follow_states.cpp +++ b/irobot_create_common/irobot_create_nodes/src/motion_control/wall_follow_states.cpp @@ -166,8 +166,8 @@ bool ObstacleInFront::get_next_velocity( { // Summarize IR sensors auto obstacle_in_sensors = [this](const std::vector & sensors, - const irobot_create_msgs::msg::IrIntensityVector & ir_intensity, - int16_t min_obs_threshold, int16_t & obs_val) -> bool { + const irobot_create_msgs::msg::IrIntensityVector & ir_intensity, + int16_t min_obs_threshold, int16_t & obs_val) -> bool { for (const auto & frame : sensors) { auto frame_it = std::find_if( ir_intensity.readings.begin(), diff --git a/irobot_create_common/irobot_create_nodes/src/motion_control_node.cpp b/irobot_create_common/irobot_create_nodes/src/motion_control_node.cpp index 77ba54bf..4ba32c2a 100644 --- a/irobot_create_common/irobot_create_nodes/src/motion_control_node.cpp +++ b/irobot_create_common/irobot_create_nodes/src/motion_control_node.cpp @@ -333,7 +333,8 @@ void MotionControlNode::hazard_vector_callback( reflex_behavior_->update_hazards(current_state_); } -void MotionControlNode::commanded_velocity_callback(geometry_msgs::msg::TwistStamped::ConstSharedPtr msg) +void MotionControlNode::commanded_velocity_callback( + geometry_msgs::msg::TwistStamped::ConstSharedPtr msg) { if (scheduler_->has_behavior()) { const auto time_now = this->now(); @@ -353,7 +354,8 @@ void MotionControlNode::commanded_velocity_callback(geometry_msgs::msg::TwistSta } -void MotionControlNode::commanded_velocity_unstamped_callback(geometry_msgs::msg::Twist::ConstSharedPtr msg) +void MotionControlNode::commanded_velocity_unstamped_callback( + geometry_msgs::msg::Twist::ConstSharedPtr msg) { geometry_msgs::msg::TwistStamped stamped_msg; stamped_msg.twist = *msg; diff --git a/irobot_create_gz/irobot_create_gz_bringup/launch/sim.launch.py b/irobot_create_gz/irobot_create_gz_bringup/launch/sim.launch.py index 7d5694fd..28e64bdc 100644 --- a/irobot_create_gz/irobot_create_gz_bringup/launch/sim.launch.py +++ b/irobot_create_gz/irobot_create_gz_bringup/launch/sim.launch.py @@ -47,7 +47,7 @@ def generate_launch_description(): gz_gui_plugin_path = SetEnvironmentVariable( name='GZ_GUI_PLUGIN_PATH', - value=":".join([ + value=':'.join([ os.path.join(pkg_irobot_create_gz_plugins, 'lib') ]) ) @@ -59,15 +59,17 @@ def generate_launch_description(): # Ignition gazebo gz_sim = IncludeLaunchDescription( PythonLaunchDescriptionSource([gz_sim_launch]), - launch_arguments=[ - ('gz_args', [LaunchConfiguration('world'), - '.sdf', - ' -v 4', - ' --gui-config ', - PathJoinSubstitution([pkg_irobot_create_gz_bringup, - 'gui', 'create3', 'gui.config']) - ]) - ] + launch_arguments=[( + 'gz_args', [ + LaunchConfiguration('world'), + '.sdf', + ' -v 4', + ' --gui-config ', + PathJoinSubstitution( + [pkg_irobot_create_gz_bringup, 'gui', 'create3', 'gui.config'] + ) + ] + )] ) # clock bridge diff --git a/irobot_create_gz/irobot_create_gz_plugins/Create3Hmi/Create3Hmi.hh b/irobot_create_gz/irobot_create_gz_plugins/Create3Hmi/Create3Hmi.hh index c9a4578b..6ca10104 100644 --- a/irobot_create_gz/irobot_create_gz_plugins/Create3Hmi/Create3Hmi.hh +++ b/irobot_create_gz/irobot_create_gz_plugins/Create3Hmi/Create3Hmi.hh @@ -68,6 +68,6 @@ private: } // namespace gui -} // namespace ignition +} // namespace gz #endif // IROBOT_CREATE_GZ__IROBOT_CREATE_GZ_PLUGINS__CREATE3HMI__CREATE3HMI_HH_