ROS Resources: Documentation | Support | Discussion Forum | Index | Service Status | ros @ Robotics Stack Exchange
Ask Your Question
0

How to use move group interface in a sub function?

asked 2019-10-07 02:14:02 -0500

A_YIng gravatar image

updated 2019-10-07 02:15:07 -0500

Hello,

Because my robot have 3 different targets need to reach in a loop, I want to merge the same line of each move group in a sub function to let the whole program more easy to read.

I think it will look like this:

void move_robot (moveit::planning_interface::MoveGroupInterface group, geometry_msgs::PoseStamped ObjectPose)
{
  group.setStartState(*group.getCurrentState());
  group.setPoseTarget(ObjectPose);

  moveit::planning_interface::MoveGroupInterface::Plan group_Planer;
  bool success = (group.plan(group_Planer) == moveit::planning_interface::MoveItErrorCode::SUCCESS);
  if (success)
  {
    ros::Duration(1).sleep();
    group.execute(group_Planer);
  }
  group.clearPoseTargets();
  ros::Duration(1).sleep();
}

int main(int argc, char **argv)
{
  ros::init(argc, argv, "move");
  ros::NodeHandle nh;

  ros::AsyncSpinner spinner(1);
  spinner.start();

  moveit::planning_interface::MoveGroupInterface group("manipulator");
  move_robot(group, pose1);
  move_robot(group, pose2);
  move_robot(group, pose3);

  return 0;
}

I got some error in this form, so I would like to know how to modify and run it. Thank for your answer!

edit retag flag offensive close merge delete

1 Answer

Sort by ยป oldest newest most voted
0

answered 2019-10-07 03:08:00 -0500

A_YIng gravatar image

I found the example code on MoveIt! tutorials website.

void move_robot (moveit::planning_interface::MoveGroupInterface &group, geometry_msgs::PoseStamped Pose)
{
  group.setStartState(*group.getCurrentState());
  group.setPoseTarget(Pose);

  moveit::planning_interface::MoveGroupInterface::Plan group_Planer;
  bool success = (group.plan(group_Planer) == moveit::planning_interface::MoveItErrorCode::SUCCESS);
  if (success)
  {
    ros::Duration(1).sleep();
    group.execute(group_Planer);
  }
  group.clearPoseTargets();
  ros::Duration(1).sleep();
}

int main(int argc, char **argv)
{
  ros::init(argc, argv, "move");
  ros::NodeHandle nh;

  ros::AsyncSpinner spinner(1);
  spinner.start();

  moveit::planning_interface::MoveGroupInterface group("manipulator");
  move_robot(group, pose1);
  move_robot(group, pose2);
  move_robot(group, pose3);

  return 0;
}
edit flag offensive delete link more

Question Tools

2 followers

Stats

Asked: 2019-10-07 02:14:02 -0500

Seen: 233 times

Last updated: Oct 07 '19