Skip to content

Commit

Permalink
Use ! in place of not keyword for Pilz and CHOMP planners (#3217) (#3221
Browse files Browse the repository at this point in the history
)

Co-authored-by: JafarAbdi <[email protected]>
(cherry picked from commit 549a2ee)

Co-authored-by: Silvio Traversaro <[email protected]>
  • Loading branch information
mergify[bot] and traversaro authored Jan 10, 2025
1 parent 9d5c520 commit 51de436
Show file tree
Hide file tree
Showing 2 changed files with 2 additions and 2 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -260,7 +260,7 @@ bool ChompPlanner::solve(const planning_scene::PlanningSceneConstPtr& planning_s
res.processing_time_[0] = std::chrono::duration<double>(std::chrono::system_clock::now() - start_time).count();

// report planning failure if path has collisions
if (not optimizer->isCollisionFree())
if (!optimizer->isCollisionFree())
{
RCLCPP_ERROR(LOGGER, "Motion plan is invalid.");
res.error_code_.val = moveit_msgs::msg::MoveItErrorCodes::INVALID_MOTION_PLAN;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -32,7 +32,7 @@ namespace
template <typename T>
void declare_parameter(const rclcpp::Node::SharedPtr& node, const std::string& name, T default_value)
{
if (not node->has_parameter(name))
if (!node->has_parameter(name))
{
node->declare_parameter<T>(name, default_value);
}
Expand Down

0 comments on commit 51de436

Please sign in to comment.