change gripper control from moveit to ros2_control
This commit is contained in:
parent
27271c0e06
commit
b4339edc19
13 changed files with 116 additions and 43 deletions
|
@ -18,6 +18,7 @@
|
|||
// moveit libs
|
||||
#include "moveit/move_group_interface/move_group_interface.h"
|
||||
#include "moveit/planning_interface/planning_interface.h"
|
||||
#include "moveit/robot_model_loader/robot_model_loader.h"
|
||||
|
||||
/*
|
||||
#include <tf2/LinearMath/Quaternion.h>
|
||||
|
@ -109,9 +110,12 @@ private:
|
|||
RCLCPP_INFO(this->get_logger(), "Executing action goal");
|
||||
const auto goal = goal_handle->get_goal();
|
||||
auto result = std::make_shared<MoveitSendPose::Result>();
|
||||
|
||||
|
||||
moveit::planning_interface::MoveGroupInterface move_group_interface(node_, goal->robot_name);
|
||||
|
||||
std::copy(move_group_interface.getJointModelGroupNames().begin(), move_group_interface.getJointModelGroupNames().end(),
|
||||
std::ostream_iterator<std::string>(std::cout, ", "));
|
||||
move_group_interface.setStartState(*move_group_interface.getCurrentState());
|
||||
move_group_interface.setPoseTarget(goal->target_pose);
|
||||
move_group_interface.setMaxVelocityScalingFactor(goal->end_effector_velocity);
|
||||
move_group_interface.setMaxAccelerationScalingFactor(goal->end_effector_acceleration);
|
||||
|
@ -121,7 +125,7 @@ private:
|
|||
if(success)
|
||||
{
|
||||
RCLCPP_INFO(this->get_logger(), "Planning success");
|
||||
move_group_interface.execute(plan);
|
||||
//move_group_interface.execute(plan);
|
||||
move_group_interface.move();
|
||||
}else{
|
||||
RCLCPP_WARN(this->get_logger(), "Failed to generate plan");
|
||||
|
|
Loading…
Add table
Add a link
Reference in a new issue