Skip to content

Commit

Permalink
Apply clang-tidy fixes and remove invalid "react" function call
Browse files Browse the repository at this point in the history
  • Loading branch information
sjahr committed Jan 6, 2021
1 parent 1d195b6 commit 64b4a81
Show file tree
Hide file tree
Showing 5 changed files with 33 additions and 37 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -80,19 +80,19 @@ GlobalPlannerComponent::GlobalPlannerComponent(const rclcpp::NodeOptions& option

// Initialize global planner after construction
timer_ = this->create_wall_timer(std::chrono::milliseconds(1), [this]() {
switch (initialized_)
if (initialized_)
{
case true:
timer_->cancel();
}
else
{
initialized_ = this->init();
if (!initialized_)
{
const std::string error = "Failed to initialize global planner";
timer_->cancel();
break;
case false:
initialized_ = this->init();
if (!initialized_)
{
const std::string error = "Failed to initialize global planner";
RCLCPP_FATAL(LOGGER, error);
}
break;
throw std::runtime_error(error);
}
}
});
}
Expand Down Expand Up @@ -218,4 +218,4 @@ moveit_msgs::msg::MotionPlanResponse GlobalPlannerComponent::plan(moveit_msgs::m

// Register the component with class_loader
#include <rclcpp_components/register_node_macro.hpp>
RCLCPP_COMPONENTS_REGISTER_NODE(moveit_hybrid_planning::GlobalPlannerComponent)
RCLCPP_COMPONENTS_REGISTER_NODE(moveit_hybrid_planning::GlobalPlannerComponent)
Original file line number Diff line number Diff line change
Expand Up @@ -74,7 +74,7 @@ class PlannerLogicInterface
* @return true if reaction was successful
*/
virtual bool react(std::string event) = 0;
~PlannerLogicInterface(){};
virtual ~PlannerLogicInterface(){};

protected:
/** \brief Constructor */
Expand All @@ -83,4 +83,4 @@ class PlannerLogicInterface
// Handle to access communication interfaces and member functions of hybrid planning manager instance that uses the planner plugin
std::shared_ptr<moveit_hybrid_planning::HybridPlanningManager> hybrid_planner_handle_ = nullptr;
};
} // namespace moveit_hybrid_planning
} // namespace moveit_hybrid_planning
Original file line number Diff line number Diff line change
Expand Up @@ -48,21 +48,19 @@ HybridPlanningManager::HybridPlanningManager(const rclcpp::NodeOptions& options)
initialized_ = false;
// Initialize hybrid planning component after after construction
timer_ = this->create_wall_timer(std::chrono::milliseconds(1), [this]() {
switch (initialized_)
if (initialized_)
{
case true:
timer_->cancel();
}
else
{
if (!this->initialize())
{
const std::string error = "Failed to initialize global planner";
timer_->cancel();
break;
case false:
if (!this->initialize())
{
const std::string error = "Failed to initialize global planner";
RCLCPP_FATAL(LOGGER, error);
throw std::runtime_error(error);
timer_->cancel();
}
initialized_ = true;
break;
throw std::runtime_error(error);
}
initialized_ = true;
}
});
}
Expand Down Expand Up @@ -131,8 +129,6 @@ bool HybridPlanningManager::initialize()
[this](const rclcpp_action::GoalUUID& /*unused*/,
std::shared_ptr<const moveit_msgs::action::HybridPlanning::Goal> /*unused*/) {
RCLCPP_INFO(LOGGER, "Received goal request");
planner_logic_instance_->react(
moveit_hybrid_planning::BasicHybridPlanningEvent::HYBRID_PLANNING_REQUEST_RECEIVED);
return rclcpp_action::GoalResponse::ACCEPT_AND_EXECUTE;
},
[](const std::shared_ptr<rclcpp_action::ServerGoalHandle<moveit_msgs::action::HybridPlanning>>& /*unused*/) {
Expand All @@ -157,7 +153,7 @@ bool HybridPlanningManager::planGlobalTrajectory()
// Add goal response callback
send_goal_options.goal_response_callback =
[this](std::shared_future<rclcpp_action::ClientGoalHandle<moveit_msgs::action::GlobalPlanner>::SharedPtr> future) {
auto goal_handle = future.get();
auto const& goal_handle = future.get();
auto planning_progress = std::make_shared<moveit_msgs::action::HybridPlanning::Feedback>();
auto& feedback = planning_progress->feedback;
if (!goal_handle)
Expand Down Expand Up @@ -194,7 +190,7 @@ bool HybridPlanningManager::runLocalPlanner()
// Add goal response callback
send_goal_options.goal_response_callback =
[this](std::shared_future<rclcpp_action::ClientGoalHandle<moveit_msgs::action::LocalPlanner>::SharedPtr> future) {
auto goal_handle = future.get();
auto const& goal_handle = future.get();
auto planning_progress = std::make_shared<moveit_msgs::action::HybridPlanning::Feedback>();
auto& feedback = planning_progress->feedback;
if (!goal_handle)
Expand Down
10 changes: 5 additions & 5 deletions moveit_ros/hybrid_planning/test/hybrid_planning_test_node.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -87,13 +87,13 @@ class HybridPlanningDemo
}

// Setup motion planning goal taken from motion_planning_api tutorial
const std::string PLANNING_GROUP = "panda_arm";
const std::string planning_group = "panda_arm";
robot_model_loader::RobotModelLoader robot_model_loader(node_, "robot_description");
const moveit::core::RobotModelPtr& robot_model = robot_model_loader.getModel();

// Create a RobotState and JointModelGroup
moveit::core::RobotStatePtr robot_state(new moveit::core::RobotState(robot_model));
const moveit::core::JointModelGroup* joint_model_group = robot_state->getJointModelGroup(PLANNING_GROUP);
const moveit::core::JointModelGroup* joint_model_group = robot_state->getJointModelGroup(planning_group);

planning_scene::PlanningScenePtr planning_scene(new planning_scene::PlanningScene(robot_model));
// Configure a valid robot state
Expand All @@ -102,7 +102,7 @@ class HybridPlanningDemo
auto goal_msg = moveit_msgs::action::HybridPlanning::Goal();

moveit::core::robotStateToRobotStateMsg(planning_scene->getCurrentStateNonConst(), goal_msg.request.start_state);
goal_msg.request.group_name = PLANNING_GROUP;
goal_msg.request.group_name = planning_group;
goal_msg.request.num_planning_attempts = 10;
goal_msg.request.max_velocity_scaling_factor = 1.0;
goal_msg.request.max_acceleration_scaling_factor = 1.0;
Expand Down Expand Up @@ -138,7 +138,7 @@ class HybridPlanningDemo
}
};
send_goal_options.feedback_callback =
[](rclcpp_action::ClientGoalHandle<moveit_msgs::action::HybridPlanning>::SharedPtr,
[](rclcpp_action::ClientGoalHandle<moveit_msgs::action::HybridPlanning>::SharedPtr /*unused*/,
const std::shared_ptr<const moveit_msgs::action::HybridPlanning::Feedback> feedback) {
RCLCPP_INFO(LOGGER, feedback->feedback);
};
Expand Down Expand Up @@ -176,4 +176,4 @@ int main(int argc, char** argv)
run_demo.join();

return 0;
}
}
Original file line number Diff line number Diff line change
Expand Up @@ -124,4 +124,4 @@ def generate_launch_description():
output='screen',
parameters=[robot_description, robot_description_semantic])

return launch.LaunchDescription([container, static_tf, rviz_node, robot_state_publisher, test_request_node, fake_joint_driver_node])
return launch.LaunchDescription([container, static_tf, rviz_node, robot_state_publisher, test_request_node, fake_joint_driver_node])

0 comments on commit 64b4a81

Please sign in to comment.