Skip to content

Commit

Permalink
Linter fixes
Browse files Browse the repository at this point in the history
  • Loading branch information
civerachb-cpr committed Aug 16, 2024
1 parent 1b0ecf4 commit 447f8f6
Show file tree
Hide file tree
Showing 5 changed files with 23 additions and 19 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -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.
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -166,8 +166,8 @@ bool ObstacleInFront::get_next_velocity(
{
// Summarize IR sensors
auto obstacle_in_sensors = [this](const std::vector<std::string> & 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(),
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -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();
Expand All @@ -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;
Expand Down
22 changes: 12 additions & 10 deletions irobot_create_gz/irobot_create_gz_bringup/launch/sim.launch.py
Original file line number Diff line number Diff line change
Expand Up @@ -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')
])
)
Expand All @@ -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
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -68,6 +68,6 @@ private:

} // namespace gui

} // namespace ignition
} // namespace gz

#endif // IROBOT_CREATE_GZ__IROBOT_CREATE_GZ_PLUGINS__CREATE3HMI__CREATE3HMI_HH_

0 comments on commit 447f8f6

Please sign in to comment.