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

Add velocity based polygon #3708

Merged
merged 36 commits into from
Feb 5, 2024
Merged
Show file tree
Hide file tree
Changes from 29 commits
Commits
Show all changes
36 commits
Select commit Hold shift + click to select a range
a2622f7
add velocity based polygon
kaichie Jul 23, 2023
ac4045f
fix header, copyright and variable name change
kaichie Jul 24, 2023
763b432
optimise polygon update
kaichie Jul 24, 2023
489392a
optimise duplicated code with setPolygonShape
kaichie Jul 24, 2023
727060c
add warning log for uncovered speed
kaichie Jul 24, 2023
3d9e979
Merge remote-tracking branch 'upstream/main' into add_polygon_velocity
kaichie Sep 2, 2023
50fd22c
update feedback
kaichie Sep 3, 2023
b6a05e2
rename polygon velocity to velocity polygon
kaichie Sep 3, 2023
b0a1093
cleanup
kaichie Sep 3, 2023
f1de5f9
fix typo
kaichie Sep 3, 2023
43c28d0
add dynamic support for velocity polygon
kaichie Sep 24, 2023
c2098b6
Merge remote-tracking branch 'upstream/main' into add_polygon_velocity
kaichie Sep 24, 2023
f6b2b19
wrap try catch for getting parameters
kaichie Sep 24, 2023
7f9f55a
update naming and linting
kaichie Sep 24, 2023
1230ede
use switch case
kaichie Sep 25, 2023
cd1af8a
Revert "use switch case"
kaichie Sep 26, 2023
2c4181e
fix proper return for invalid parameters
kaichie Sep 26, 2023
400d45e
remove topic parameter for velocity polygon
kaichie Sep 26, 2023
b97cbb7
fix formatting manually
kaichie Sep 26, 2023
5dc403b
continue if points are not defined
kaichie Sep 26, 2023
3db0146
Merge branch 'main' into add_polygon_velocity
kaichie Nov 16, 2023
8491ed4
Merge branch 'main' into add_polygon_velocity
kaichie Dec 5, 2023
a5c48a7
Merge branch 'main' into add_polygon_velocity
kaichie Jan 2, 2024
abab066
rewrite velocity polygon with polygon base class
kaichie Jan 7, 2024
620c7c2
update review comments and description
kaichie Jan 7, 2024
898d8c0
add VelocityPolygon to detector node
kaichie Jan 7, 2024
940225c
review update
kaichie Jan 16, 2024
0a7fe8c
fix cpplint
kaichie Jan 16, 2024
680f7ca
Merge remote-tracking branch 'upstream/main' into add_polygon_velocity
kaichie Jan 16, 2024
5c5d184
Update nav2_collision_monitor/src/velocity_polygon.cpp
kaichie Jan 17, 2024
49d7b71
add velocity polygon tests
kaichie Jan 17, 2024
ee69105
fix cpplint
kaichie Jan 17, 2024
10d59e1
add in-line comment
kaichie Jan 17, 2024
bbcb930
fix push back
kaichie Jan 17, 2024
df2cb95
minor change and update README
kaichie Jan 20, 2024
e150e85
update README
kaichie Jan 27, 2024
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
2 changes: 2 additions & 0 deletions nav2_collision_monitor/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -49,6 +49,7 @@ set(detector_library_name ${detector_executable_name}_core)
add_library(${monitor_library_name} SHARED
src/collision_monitor_node.cpp
src/polygon.cpp
src/velocity_polygon.cpp
src/circle.cpp
src/source.cpp
src/scan.cpp
Expand All @@ -59,6 +60,7 @@ add_library(${monitor_library_name} SHARED
add_library(${detector_library_name} SHARED
src/collision_detector_node.cpp
src/polygon.cpp
src/velocity_polygon.cpp
SteveMacenski marked this conversation as resolved.
Show resolved Hide resolved
src/circle.cpp
src/source.cpp
src/scan.cpp
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -33,6 +33,7 @@
#include "nav2_collision_monitor/types.hpp"
#include "nav2_collision_monitor/polygon.hpp"
#include "nav2_collision_monitor/circle.hpp"
#include "nav2_collision_monitor/velocity_polygon.hpp"
#include "nav2_collision_monitor/source.hpp"
#include "nav2_collision_monitor/scan.hpp"
#include "nav2_collision_monitor/pointcloud.hpp"
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -33,6 +33,7 @@
#include "nav2_collision_monitor/types.hpp"
#include "nav2_collision_monitor/polygon.hpp"
#include "nav2_collision_monitor/circle.hpp"
#include "nav2_collision_monitor/velocity_polygon.hpp"
#include "nav2_collision_monitor/source.hpp"
#include "nav2_collision_monitor/scan.hpp"
#include "nav2_collision_monitor/pointcloud.hpp"
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -135,7 +135,7 @@ class Polygon
/**
* @brief Updates polygon from footprint subscriber (if any)
*/
void updatePolygon();
virtual void updatePolygon(const Velocity & /*cmd_vel_in*/);

/**
* @brief Gets number of points inside given polygon
Expand Down
Original file line number Diff line number Diff line change
@@ -0,0 +1,115 @@
// Copyright (c) 2023 Dexory
//
// 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_COLLISION_MONITOR__VELOCITY_POLYGON_HPP_
#define NAV2_COLLISION_MONITOR__VELOCITY_POLYGON_HPP_

#include <memory>
#include <string>
#include <vector>

#include "geometry_msgs/msg/polygon_stamped.hpp"
#include "nav2_collision_monitor/polygon.hpp"
#include "nav2_collision_monitor/types.hpp"
#include "nav2_util/lifecycle_node.hpp"
#include "rclcpp/rclcpp.hpp"
#include "tf2_ros/buffer.h"

namespace nav2_collision_monitor
{

/**
* @brief Velocity polygon class.
* This class contains all the points of the polygon and
* the expected condition of the velocity based polygon.
*/
class VelocityPolygon : public Polygon
SteveMacenski marked this conversation as resolved.
Show resolved Hide resolved
{
public:
/**
* @brief VelocityPolygon constructor
* @param node Collision Monitor node pointer
* @param polygon_name Name of main polygon
*/
VelocityPolygon(
const nav2_util::LifecycleNode::WeakPtr & node, const std::string & polygon_name,
const std::shared_ptr<tf2_ros::Buffer> tf_buffer, const std::string & base_frame_id,
const tf2::Duration & transform_tolerance);
/**
* @brief VelocityPolygon destructor
*/
virtual ~VelocityPolygon();

/**
* @brief Overriden getParameters function for VelocityPolygon parameters
* @param polygon_sub_topic Not used in VelocityPolygon
* @param polygon_pub_topic Output name of polygon publishing topic
* @param footprint_topic Not used in VelocityPolygon
* @return True if all parameters were obtained or false in failure case
*/
bool getParameters(
std::string & /*polygon_sub_topic*/, std::string & polygon_pub_topic,
std::string & /*footprint_topic*/) override;

protected:
/**
* @brief Custom struc to store the parameters of the sub-polygon
* @param poly_ The points of the sub-polygon
* @param velocity_polygon_name_ The name of the sub-polygon
* @param linear_min_ The minimum linear velocity
* @param linear_max_ The maximum linear velocity
* @param theta_min_ The minimum angular velocity
* @param theta_max_ The maximum angular velocity
* @param direction_end_angle_ The end angle of the direction(For holonomic robot only)
* @param direction_start_angle_ The start angle of the direction(For holonomic robot only)
*/
struct SubPolygonParameter
{
std::vector<Point> poly_;
std::string velocity_polygon_name_;
double linear_min_;
double linear_max_;
double theta_min_;
double theta_max_;
double direction_end_angle_;
double direction_start_angle_;
};

/**
* @brief Overriden updatePolygon function for VelocityPolygon
* @param cmd_vel_in Robot twist command input
*/
void updatePolygon(const Velocity & cmd_vel_in) override;

/**
* @brief Check if the velocities and direction is in expected range.
* @param cmd_vel_in Robot twist command input
* @param sub_polygon_param Sub polygon parameters
* @return True if speed and direction is within the condition
*/
bool isInRange(const Velocity & cmd_vel_in, const SubPolygonParameter & sub_polygon_param);

// Clock
rclcpp::Clock::SharedPtr clock_;

// Variables
/// @brief Flag to indicate if the robot is holonomic
bool holonomic_;
/// @brief Vector to store the parameters of the sub-polygon
std::vector<SubPolygonParameter> sub_polygons_;
}; // class VelocityPolygon

} // namespace nav2_collision_monitor

#endif // NAV2_COLLISION_MONITOR__VELOCITY_POLYGON_HPP_
40 changes: 38 additions & 2 deletions nav2_collision_monitor/params/collision_monitor_params.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -11,9 +11,10 @@ collision_monitor:
stop_pub_timeout: 2.0
# Polygons represent zone around the robot for "stop", "slowdown" and "limit" action types,
# and robot footprint for "approach" action type.
# Footprint could be "polygon" type with dynamically set footprint from footprint_topic
# or "circle" type with static footprint set by radius. "footprint_topic" parameter
# (1) Footprint could be "polygon" type with dynamically set footprint from footprint_topic
# (2) "circle" type with static footprint set by radius. "footprint_topic" parameter
# to be ignored in circular case.
# (3) "velocity_polygon" type with dynamically set polygon from velocity_polygons
polygons: ["PolygonStop"]
PolygonStop:
type: "polygon"
Expand Down Expand Up @@ -51,6 +52,41 @@ collision_monitor:
min_points: 6
visualize: False
enabled: True
VelocityPolygonStop:
type: "velocity_polygon"
action_type: "stop"
time_before_collision: 2.0
simulation_time_step: 0.1
min_points: 6
visualize: True
enabled: True
polygon_pub_topic: "polygon_approach"
velocity_polygons: ["rotation", "translation_forward", "translation_backward", "stopped"]
holonomic: false
rotation:
points: "[[0.3, 0.3], [0.3, -0.3], [-0.3, -0.3], [-0.3, 0.3]]"
linear_min: 0.0
linear_max: 0.05
theta_min: -1.0
theta_max: 1.0
translation_forward:
points: "[[0.35, 0.3], [0.35, -0.3], [-0.2, -0.3], [-0.2, 0.3]]"
linear_min: 0.0
linear_max: 1.0
theta_min: -1.0
theta_max: 1.0
translation_backward:
points: "[[0.2, 0.3], [0.2, -0.3], [-0.35, -0.3], [-0.35, 0.3]]"
linear_min: -1.0
linear_max: 0.0
theta_min: -1.0
theta_max: 1.0
stopped:
points: "[[0.25, 0.25], [0.25, -0.25], [-0.25, -0.25], [-0.25, 0.25]]"
linear_min: -1.0
SteveMacenski marked this conversation as resolved.
Show resolved Hide resolved
linear_max: 1.0
theta_min: -1.0
theta_max: 1.0
observation_sources: ["scan"]
scan:
type: "scan"
Expand Down
4 changes: 4 additions & 0 deletions nav2_collision_monitor/src/collision_detector_node.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -207,6 +207,10 @@ bool CollisionDetector::configurePolygons(
polygons_.push_back(
std::make_shared<Circle>(
node, polygon_name, tf_buffer_, base_frame_id, transform_tolerance));
} else if (polygon_type == "velocity_polygon") {
polygons_.push_back(
std::make_shared<VelocityPolygon>(
node, polygon_name, tf_buffer_, base_frame_id, transform_tolerance));
} else { // Error if something else
RCLCPP_ERROR(
get_logger(),
Expand Down
6 changes: 5 additions & 1 deletion nav2_collision_monitor/src/collision_monitor_node.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -298,6 +298,10 @@ bool CollisionMonitor::configurePolygons(
polygons_.push_back(
std::make_shared<Circle>(
node, polygon_name, tf_buffer_, base_frame_id, transform_tolerance));
} else if (polygon_type == "velocity_polygon") {
polygons_.push_back(
std::make_shared<VelocityPolygon>(
node, polygon_name, tf_buffer_, base_frame_id, transform_tolerance));
} else { // Error if something else
RCLCPP_ERROR(
get_logger(),
Expand Down Expand Up @@ -451,7 +455,7 @@ void CollisionMonitor::process(const Velocity & cmd_vel_in)
}

// Update polygon coordinates
polygon->updatePolygon();
polygon->updatePolygon(cmd_vel_in);

const ActionType at = polygon->getActionType();
if (at == STOP || at == SLOWDOWN || at == LIMIT) {
Expand Down
2 changes: 1 addition & 1 deletion nav2_collision_monitor/src/polygon.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -179,7 +179,7 @@ bool Polygon::isShapeSet()
return true;
}

void Polygon::updatePolygon()
void Polygon::updatePolygon(const Velocity & /*cmd_vel_in*/)
{
if (footprint_sub_ != nullptr) {
// Get latest robot footprint from footprint subscriber
Expand Down
Loading
Loading