Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Linter fixes #2879

Merged
merged 16 commits into from
Apr 4, 2022
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 @@ -44,4 +44,4 @@ class DifferentialMotionModel : public nav2_amcl::MotionModel
double alpha1_, alpha2_, alpha3_, alpha4_, alpha5_;
};
} // namespace nav2_amcl
#endif
#endif // NAV2_AMCL__MOTION_MODEL__DIFFERENTIAL_MOTION_MODEL_HPP_
4 changes: 2 additions & 2 deletions nav2_amcl/include/nav2_amcl/motion_model/motion_model.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -18,9 +18,10 @@
#define NAV2_AMCL__MOTION_MODEL__MOTION_MODEL_HPP_

#include <string>
#include <memory>

#include "nav2_amcl/pf/pf.hpp"
#include "nav2_amcl/pf/pf_pdf.hpp"
#include <memory>

namespace nav2_amcl
{
Expand Down Expand Up @@ -55,7 +56,6 @@ class MotionModel
* @param delta change in pose in odometry update
*/
virtual void odometryUpdate(pf_t * pf, const pf_vector_t & pose, const pf_vector_t & delta) = 0;

};
} // namespace nav2_amcl

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -19,8 +19,8 @@
*
*/

#ifndef DIFFERENTIAL_MOTION_MODEL_HPP
#define DIFFERENTIAL_MOTION_MODEL_HPP
#ifndef NAV2_AMCL__MOTION_MODEL__OMNI_MOTION_MODEL_HPP_
#define NAV2_AMCL__MOTION_MODEL__OMNI_MOTION_MODEL_HPP_
SteveMacenski marked this conversation as resolved.
Show resolved Hide resolved

#include <sys/types.h>
#include <math.h>
Expand All @@ -44,4 +44,4 @@ class OmniMotionModel : public nav2_amcl::MotionModel
double alpha1_, alpha2_, alpha3_, alpha4_, alpha5_;
};
} // namespace nav2_amcl
#endif
#endif // NAV2_AMCL__MOTION_MODEL__OMNI_MOTION_MODEL_HPP_
20 changes: 20 additions & 0 deletions nav2_amcl/include/nav2_amcl/pf/eig3.hpp
Original file line number Diff line number Diff line change
@@ -1,3 +1,23 @@
/*
SteveMacenski marked this conversation as resolved.
Show resolved Hide resolved
* Player - One Hell of a Robot Server
* Copyright (C) 2000 Brian Gerkey & Kasper Stoy
* [email protected] [email protected]
*
* This library is free software; you can redistribute it and/or
* modify it under the terms of the GNU Lesser General Public
* License as published by the Free Software Foundation; either
* version 2.1 of the License, or (at your option) any later version.
*
* This library is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU
* Lesser General Public License for more details.
*
* You should have received a copy of the GNU Lesser General Public
* License along with this library; if not, write to the Free Software
* Foundation, Inc., 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA
*
*/
/* Eigen-decomposition for symmetric 3x3 real matrices.
Public domain, copied from the public domain Java library JAMA. */

Expand Down
41 changes: 41 additions & 0 deletions nav2_amcl/include/nav2_amcl/portable_utils.hpp
Original file line number Diff line number Diff line change
@@ -0,0 +1,41 @@
// Copyright (c) Samsung Research America
//
// 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 NAV2_AMCL__PORTABLE_UTILS_HPP_
#define NAV2_AMCL__PORTABLE_UTILS_HPP_

#include <stdlib.h>

#ifdef __cplusplus
extern "C" {
#endif

#ifndef HAVE_DRAND48
// Some system (e.g., Windows) doesn't come with drand48(), srand48().
// Use rand, and srand for such system.
static double drand48(void)
{
return ((double)rand()) / RAND_MAX;// NOLINT
}

static void srand48(long int seedval)// NOLINT
{
srand(seedval);
}
#endif

#ifdef __cplusplus
}
#endif

#endif // NAV2_AMCL__PORTABLE_UTILS_HPP_
2 changes: 1 addition & 1 deletion nav2_amcl/src/amcl_node.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -48,7 +48,7 @@
#include "tf2/utils.h"
#pragma GCC diagnostic pop

#include "portable_utils.h"
#include "nav2_amcl/portable_utils.hpp"

using namespace std::placeholders;
using namespace std::chrono_literals;
Expand Down
28 changes: 0 additions & 28 deletions nav2_amcl/src/include/portable_utils.h

This file was deleted.

2 changes: 1 addition & 1 deletion nav2_amcl/src/motion_model/omni_motion_model.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -88,7 +88,7 @@ OmniMotionModel::odometryUpdate(
}
}

} // namespace nav2_amcl
} // namespace nav2_amcl

#include <pluginlib/class_list_macros.hpp>
PLUGINLIB_EXPORT_CLASS(nav2_amcl::OmniMotionModel, nav2_amcl::MotionModel)
20 changes: 20 additions & 0 deletions nav2_amcl/src/pf/eig3.c
Original file line number Diff line number Diff line change
@@ -1,3 +1,23 @@
/*
* Player - One Hell of a Robot Server
* Copyright (C) 2000 Brian Gerkey & Kasper Stoy
* [email protected] [email protected]
*
* This library is free software; you can redistribute it and/or
* modify it under the terms of the GNU Lesser General Public
* License as published by the Free Software Foundation; either
* version 2.1 of the License, or (at your option) any later version.
*
* This library is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU
* Lesser General Public License for more details.
*
* You should have received a copy of the GNU Lesser General Public
* License along with this library; if not, write to the Free Software
* Foundation, Inc., 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA
*
*/
/* Eigen decomposition code for symmetric 3x3 matrices, copied from the public
domain Java Matrix library JAMA. */

Expand Down
2 changes: 1 addition & 1 deletion nav2_amcl/src/pf/pf.c
Original file line number Diff line number Diff line change
Expand Up @@ -35,7 +35,7 @@
#include "nav2_amcl/pf/pf_pdf.hpp"
#include "nav2_amcl/pf/pf_kdtree.hpp"

#include "portable_utils.h"
#include "nav2_amcl/portable_utils.hpp"


// Compute the required number of samples, given that there are k bins
Expand Down
2 changes: 1 addition & 1 deletion nav2_amcl/src/pf/pf_pdf.c
Original file line number Diff line number Diff line change
Expand Up @@ -34,7 +34,7 @@

#include "nav2_amcl/pf/pf_pdf.hpp"

#include "portable_utils.h"
#include "nav2_amcl/portable_utils.hpp"

// Random number generator seed value
static unsigned int pf_pdf_seed;
Expand Down
2 changes: 1 addition & 1 deletion nav2_costmap_2d/include/nav2_costmap_2d/costmap_2d.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -92,7 +92,7 @@ class Costmap2D
* @brief Constructor for a costmap from an OccupancyGrid map
* @param map The OccupancyGrid map to create costmap from
*/
Costmap2D(const nav_msgs::msg::OccupancyGrid & map);
explicit Costmap2D(const nav_msgs::msg::OccupancyGrid & map);

/**
* @brief Overloaded assignment operator
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -35,8 +35,8 @@
* Author: Alexey Merzlyakov
*********************************************************************/

#ifndef NAV2_COSTMAP_2D__COSTMAP_FILTER_HPP_
#define NAV2_COSTMAP_2D__COSTMAP_FILTER_HPP_
#ifndef NAV2_COSTMAP_2D__COSTMAP_FILTERS__COSTMAP_FILTER_HPP_
#define NAV2_COSTMAP_2D__COSTMAP_FILTERS__COSTMAP_FILTER_HPP_

#include <string>
#include <mutex>
Expand Down Expand Up @@ -78,7 +78,7 @@ class CostmapFilter : public Layer
/**
* @brief Initialization process of layer on startup
*/
virtual void onInitialize() final;
void onInitialize() final;

/**
* @brief Update the bounds of the master costmap by this layer's update dimensions
Expand All @@ -90,7 +90,7 @@ class CostmapFilter : public Layer
* @param max_x X max map coord of the window to update
* @param max_y Y max map coord of the window to update
*/
virtual void updateBounds(
void updateBounds(
double robot_x, double robot_y, double robot_yaw,
double * min_x, double * min_y, double * max_x, double * max_y) final;

Expand All @@ -102,27 +102,27 @@ class CostmapFilter : public Layer
* @param max_x X max map coord of the window to update
* @param max_y Y max map coord of the window to update
*/
virtual void updateCosts(
void updateCosts(
nav2_costmap_2d::Costmap2D & master_grid,
int min_i, int min_j, int max_i, int max_j) final;

/**
* @brief Activate the layer
*/
virtual void activate() final;
void activate() final;
/**
* @brief Deactivate the layer
*/
virtual void deactivate() final;
void deactivate() final;
/**
* @brief Reset the layer
*/
virtual void reset() final;
void reset() final;

/**
* @brief If clearing operations should be processed on this layer or not
*/
virtual bool isClearable() {return false;}
bool isClearable() {return false;}

/** CostmapFilter API **/
/**
Expand Down Expand Up @@ -182,4 +182,4 @@ class CostmapFilter : public Layer

} // namespace nav2_costmap_2d

#endif // NAV2_COSTMAP_2D__COSTMAP_FILTER_HPP_
#endif // NAV2_COSTMAP_2D__COSTMAP_FILTERS__COSTMAP_FILTER_HPP_
Original file line number Diff line number Diff line change
Expand Up @@ -35,8 +35,8 @@
* Author: Alexey Merzlyakov
*********************************************************************/

#ifndef NAV2_COSTMAP_2D__FILTER_VALUES_HPP_
#define NAV2_COSTMAP_2D__FILTER_VALUES_HPP_
#ifndef NAV2_COSTMAP_2D__COSTMAP_FILTERS__FILTER_VALUES_HPP_
#define NAV2_COSTMAP_2D__COSTMAP_FILTERS__FILTER_VALUES_HPP_

/** Provides constants used in costmap filters */

Expand All @@ -59,4 +59,4 @@ static constexpr double NO_SPEED_LIMIT = 0.0;

} // namespace nav2_costmap_2d

#endif // NAV2_COSTMAP_2D__FILTER_VALUES_HPP_
#endif // NAV2_COSTMAP_2D__COSTMAP_FILTERS__FILTER_VALUES_HPP_
Original file line number Diff line number Diff line change
Expand Up @@ -35,14 +35,14 @@
* Author: Alexey Merzlyakov
*********************************************************************/

#ifndef NAV2_COSTMAP_2D__KEEPOUT_FILTER_HPP_
#define NAV2_COSTMAP_2D__KEEPOUT_FILTER_HPP_

#include "nav2_costmap_2d/costmap_filters/costmap_filter.hpp"
#ifndef NAV2_COSTMAP_2D__COSTMAP_FILTERS__KEEPOUT_FILTER_HPP_
#define NAV2_COSTMAP_2D__COSTMAP_FILTERS__KEEPOUT_FILTER_HPP_

#include <string>
#include <memory>

#include "nav2_costmap_2d/costmap_filters/costmap_filter.hpp"

#include "rclcpp/rclcpp.hpp"
#include "nav_msgs/msg/occupancy_grid.hpp"
#include "nav2_msgs/msg/costmap_filter_info.hpp"
Expand Down Expand Up @@ -108,4 +108,4 @@ class KeepoutFilter : public CostmapFilter

} // namespace nav2_costmap_2d

#endif // NAV2_COSTMAP_2D__KEEPOUT_FILTER_HPP_
#endif // NAV2_COSTMAP_2D__COSTMAP_FILTERS__KEEPOUT_FILTER_HPP_
Original file line number Diff line number Diff line change
Expand Up @@ -35,17 +35,18 @@
* Author: Alexey Merzlyakov
*********************************************************************/

#ifndef NAV2_COSTMAP_2D__SPEED_FILTER_HPP_
#define NAV2_COSTMAP_2D__SPEED_FILTER_HPP_
#ifndef NAV2_COSTMAP_2D__COSTMAP_FILTERS__SPEED_FILTER_HPP_
#define NAV2_COSTMAP_2D__COSTMAP_FILTERS__SPEED_FILTER_HPP_

#include <memory>
#include <string>

#include "nav2_costmap_2d/costmap_filters/costmap_filter.hpp"

#include "nav_msgs/msg/occupancy_grid.hpp"
#include "nav2_msgs/msg/costmap_filter_info.hpp"
#include "nav2_msgs/msg/speed_limit.hpp"

#include <memory>

namespace nav2_costmap_2d
{
/**
Expand Down Expand Up @@ -144,4 +145,4 @@ class SpeedFilter : public CostmapFilter

} // namespace nav2_costmap_2d

#endif // NAV2_COSTMAP_2D__SPEED_FILTER_HPP_
#endif // NAV2_COSTMAP_2D__COSTMAP_FILTERS__SPEED_FILTER_HPP_
1 change: 1 addition & 0 deletions nav2_costmap_2d/include/nav2_costmap_2d/static_layer.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -40,6 +40,7 @@

#include <mutex>
#include <string>
#include <vector>

#include "map_msgs/msg/occupancy_grid_update.hpp"
#include "message_filters/subscriber.h"
Expand Down
4 changes: 3 additions & 1 deletion nav2_costmap_2d/include/nav2_costmap_2d/voxel_layer.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -38,6 +38,9 @@
#ifndef NAV2_COSTMAP_2D__VOXEL_LAYER_HPP_
#define NAV2_COSTMAP_2D__VOXEL_LAYER_HPP_

#include <vector>
#include "message_filters/subscriber.h"

#include <rclcpp/rclcpp.hpp>
#include <nav2_costmap_2d/layer.hpp>
#include <nav2_costmap_2d/layered_costmap.hpp>
Expand All @@ -48,7 +51,6 @@
#include <laser_geometry/laser_geometry.hpp>
#include <sensor_msgs/msg/point_cloud.hpp>
#include <sensor_msgs/msg/point_cloud2.hpp>
#include <message_filters/subscriber.h>
#include <nav2_costmap_2d/obstacle_layer.hpp>
#include <nav2_voxel_grid/voxel_grid.hpp>

Expand Down
Loading