Skip to content
Open
Show file tree
Hide file tree
Changes from all commits
Commits
Show all changes
29 commits
Select commit Hold shift + click to select a range
c86e3b2
Format max_velocity and max_acceleration for YAML output as float
AimanHaidar Oct 24, 2025
38aac46
make use of max_cartesian_speed in MotionSequenceRequest
AimanHaidar Nov 5, 2025
7d70a27
use feature in circ command
AimanHaidar Nov 5, 2025
0bb71f2
organize into function
AimanHaidar Nov 5, 2025
b28883e
Merge branch 'fix/joint-limits-crash' into dev
AimanHaidar Nov 7, 2025
ce9099d
add free path planner using composite kdl path
AimanHaidar Nov 7, 2025
a0bc8e4
fix include files and add it to plugin
AimanHaidar Nov 8, 2025
4e62e81
convert to roundedComposite
AimanHaidar Nov 8, 2025
e9f63ae
fix bug andadd check of near start point to curve tip
AimanHaidar Nov 8, 2025
4008bdc
fix bug in set max cart speed before set of path
AimanHaidar Nov 8, 2025
b8e8de3
Merge branch 'feature/use-max-cartesian-speed' into feature/free-path…
AimanHaidar Nov 8, 2025
99f146b
add check request validation
AimanHaidar Nov 8, 2025
24d27ce
add function to compute the max rounding circle radius
AimanHaidar Nov 9, 2025
84a8e94
add close points check to avoid Not_Feasable error
AimanHaidar Nov 9, 2025
749d7e4
add helper class for generate free paths
AimanHaidar Nov 10, 2025
440a77d
clean code and add copyright!
AimanHaidar Nov 10, 2025
c6a0389
Merge branch 'moveit:main' into feature/free-path-generator
AimanHaidar Nov 10, 2025
7e08974
handle colinear points errors
AimanHaidar Nov 10, 2025
5072fbd
correct error massages and fix bug
AimanHaidar Nov 22, 2025
9fc413a
restrict the rounding radius to not exceed KDL epsilon
AimanHaidar Nov 24, 2025
616d427
fix bug
AimanHaidar Nov 24, 2025
ab5d654
fix:compute rounding(blend) radius after filtering near points
AimanHaidar Nov 24, 2025
5f7a8ba
change name to polyline
AimanHaidar Dec 1, 2025
d5ce36c
change files' names
AimanHaidar Dec 1, 2025
b1df424
rename
AimanHaidar Dec 1, 2025
61c8742
fix jazzy-ci issue
AimanHaidar Dec 1, 2025
0120591
add test for the cartesian max speed
AimanHaidar Dec 2, 2025
ef3294f
Revert "Format max_velocity and max_acceleration for YAML output as f…
AimanHaidar Dec 2, 2025
7bd69b7
Merge branch 'main' into feature/free-path-generator
AimanHaidar Dec 3, 2025
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
12 changes: 12 additions & 0 deletions moveit_planners/pilz_industrial_motion_planner/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -127,6 +127,17 @@ ament_target_dependencies(planning_context_loader_circ
target_link_libraries(planning_context_loader_circ planning_context_loader_base
joint_limits_common trajectory_generation_common)

add_library(
planning_context_loader_polyline SHARED
src/planning_context_loader_polyline.cpp
src/trajectory_generator_polyline.cpp src/velocity_profile_atrap.cpp
src/path_polyline_generator.cpp)
ament_target_dependencies(planning_context_loader_polyline
${THIS_PACKAGE_INCLUDE_DEPENDS})
target_link_libraries(
planning_context_loader_polyline planning_context_loader_base
joint_limits_common trajectory_generation_common)

add_library(sequence_capability SHARED src/move_group_sequence_action.cpp
src/move_group_sequence_service.cpp)
ament_target_dependencies(sequence_capability ${THIS_PACKAGE_INCLUDE_DEPENDS})
Expand All @@ -153,6 +164,7 @@ install(
planning_context_loader_ptp
planning_context_loader_lin
planning_context_loader_circ
planning_context_loader_polyline
command_list_manager
sequence_capability
trajectory_generation_common
Expand Down
Original file line number Diff line number Diff line change
@@ -0,0 +1,50 @@

/*********************************************************************
* All MoveIt 2 headers have been updated to use the .hpp extension.
*
* .h headers are now autogenerated via create_deprecated_headers.py,
* and will import the corresponding .hpp with a deprecation warning.
*
* imports via .h files may be removed in future releases, so please
* modify your imports to use the corresponding .hpp imports.
*
* See https://github.com/moveit/moveit2/pull/3113 for extra details.
*********************************************************************/
/*********************************************************************
* Software License Agreement (BSD License)
*
* Copyright (c) 2018 Pilz GmbH & Co. KG
* Copyright (c) 2025 Aiman Haidar
* All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
*
* * Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* * Redistributions in binary form must reproduce the above
* copyright notice, this list of conditions and the following
* disclaimer in the documentation and/or other materials provided
* with the distribution.
* * Neither the name of Pilz GmbH & Co. KG nor the names of its
* contributors may be used to endorse or promote products derived
* from this software without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*********************************************************************/

#pragma once
#pragma message(".h header is obsolete. Please use the .hpp header instead.")
#include <pilz_industrial_motion_planner/path_polyline_generator.hpp>
Original file line number Diff line number Diff line change
@@ -0,0 +1,99 @@
/*********************************************************************
* Software License Agreement (BSD License)
*
* Copyright (c) 2018 Pilz GmbH & Co. KG
* Copyright (c) 2025 Aiman Haidar
* All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
*
* * Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* * Redistributions in binary form must reproduce the above
* copyright notice, this list of conditions and the following
* disclaimer in the documentation and/or other materials provided
* with the distribution.
* * Neither the name of Pilz GmbH & Co. KG nor the names of its
* contributors may be used to endorse or promote products derived
* from this software without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*********************************************************************/

#pragma once

#include <kdl/path.hpp>
#include <kdl/path_roundedcomposite.hpp>
#include <kdl/rotational_interpolation_sa.hpp>
#include <kdl/utilities/error.h>

#include <memory>

namespace pilz_industrial_motion_planner
{
/**
* @brief Generator class for KDL::Path_RoundedComposite from different polyline path
* representations
*/
class PathPolylineGenerator
{
public:
/**
* @brief set the path polyline from waypoints
*
*/
static std::unique_ptr<KDL::Path> polylineFromWaypoints(const KDL::Frame& start_pose,
const std::vector<KDL::Frame>& waypoints,
KDL::RotationalInterpolation* rot_interpo, double smoothness,
double eqradius);

/**
* @brief compute the maximum rounding radius from KDL::Path_RoundedComosite
* @param waypoints_: waypoints defining the path
* @param smoothness: smoothness level [0..1] scaling the maximum blend radius
* @return maximum blend radius
*/
static std::vector<KDL::Frame> filterWaypoints(const KDL::Frame& start_pose, const std::vector<KDL::Frame>& waypoints);
static double computeBlendRadius(const std::vector<KDL::Frame>& waypoints_, double smoothness);
static void checkConsecutiveColinearWaypoints(const KDL::Frame& p1, const KDL::Frame& p2, const KDL::Frame& p3);

private:
PathPolylineGenerator(){}; // no instantiation of this helper class!

static constexpr double MIN_SEGMENT_LENGTH{ 0.2e-3 };
static constexpr double MIN_SMOOTHNESS{ 0.01 };
static constexpr double MAX_SMOOTHNESS{ 0.99 };
static constexpr double MIN_COLINEAR_NORM{ 1e-9 };
};

class ErrorMotionPlanningColinearConsicutiveWaypoints : public KDL::Error_MotionPlanning
{
public:
const char* Description() const override
{
return "Three collinear consecutive waypoints."
" A Polyline Path cannot be created.";
}
int GetType() const override
{
return ERROR_CODE_COLINEAR_CONSECUTIVE_WAYPOINTS;
} // LCOV_EXCL_LINE

private:
static constexpr int ERROR_CODE_COLINEAR_CONSECUTIVE_WAYPOINTS{ 3104 };
};

} // namespace pilz_industrial_motion_planner
Original file line number Diff line number Diff line change
@@ -0,0 +1,50 @@

/*********************************************************************
* All MoveIt 2 headers have been updated to use the .hpp extension.
*
* .h headers are now autogenerated via create_deprecated_headers.py,
* and will import the corresponding .hpp with a deprecation warning.
*
* imports via .h files may be removed in future releases, so please
* modify your imports to use the corresponding .hpp imports.
*
* See https://github.com/moveit/moveit2/pull/3113 for extra details.
*********************************************************************/
/*********************************************************************
* Software License Agreement (BSD License)
*
* Copyright (c) 2018 Pilz GmbH & Co. KG
* Copyright (c) 2025 Aiman Haidar
* All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
*
* * Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* * Redistributions in binary form must reproduce the above
* copyright notice, this list of conditions and the following
* disclaimer in the documentation and/or other materials provided
* with the distribution.
* * Neither the name of Pilz GmbH & Co. KG nor the names of its
* contributors may be used to endorse or promote products derived
* from this software without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*********************************************************************/

#pragma once
#pragma message(".h header is obsolete. Please use the .hpp header instead.")
#include <pilz_industrial_motion_planner/planning_context_loader_polyline.hpp>
Original file line number Diff line number Diff line change
@@ -0,0 +1,69 @@
/*********************************************************************
* Software License Agreement (BSD License)
*
* Copyright (c) 2018 Pilz GmbH & Co. KG
* Copyright (c) 2025 Aiman Haidar
* All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
*
* * Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* * Redistributions in binary form must reproduce the above
* copyright notice, this list of conditions and the following
* disclaimer in the documentation and/or other materials provided
* with the distribution.
* * Neither the name of Pilz GmbH & Co. KG nor the names of its
* contributors may be used to endorse or promote products derived
* from this software without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*********************************************************************/

#pragma once

#include <pilz_industrial_motion_planner/planning_context_loader.hpp>

#include <moveit/planning_interface/planning_interface.hpp>

namespace pilz_industrial_motion_planner
{
/**
* @brief Plugin that can generate instances of PlanningContextPolyline.
* Generates instances of PlanningContextPolyline.
*/
class PlanningContextLoaderPolyline : public PlanningContextLoader
{
public:
PlanningContextLoaderPolyline();
~PlanningContextLoaderPolyline() override;

/**
* @brief return a instance of
* pilz_industrial_motion_planner::PlanningContextPolyline
* @param planning_context returned context
* @param name
* @param group
* @return true on success, false otherwise
*/
bool loadContext(planning_interface::PlanningContextPtr& planning_context, const std::string& name,
const std::string& group) const override;
};

typedef std::shared_ptr<PlanningContextLoaderPolyline> PlanningContextLoaderPolylinePtr;
typedef std::shared_ptr<const PlanningContextLoaderPolyline> PlanningContextLoaderPolylineConstPtr;

} // namespace pilz_industrial_motion_planner
Original file line number Diff line number Diff line change
@@ -0,0 +1,50 @@

/*********************************************************************
* All MoveIt 2 headers have been updated to use the .hpp extension.
*
* .h headers are now autogenerated via create_deprecated_headers.py,
* and will import the corresponding .hpp with a deprecation warning.
*
* imports via .h files may be removed in future releases, so please
* modify your imports to use the corresponding .hpp imports.
*
* See https://github.com/moveit/moveit2/pull/3113 for extra details.
*********************************************************************/
/*********************************************************************
* Software License Agreement (BSD License)
*
* Copyright (c) 2018 Pilz GmbH & Co. KG
* Copyright (c) 2025 Aiman Haidar
* All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
*
* * Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* * Redistributions in binary form must reproduce the above
* copyright notice, this list of conditions and the following
* disclaimer in the documentation and/or other materials provided
* with the distribution.
* * Neither the name of Pilz GmbH & Co. KG nor the names of its
* contributors may be used to endorse or promote products derived
* from this software without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*********************************************************************/

#pragma once
#pragma message(".h header is obsolete. Please use the .hpp header instead.")
#include <pilz_industrial_motion_planner/planning_context_polyline.hpp>
Loading