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

how do you create a group of joints for MoveIt Planning Group for a custom robot

asked 2020-07-04 21:40:35 -0500

Zonared gravatar image

updated 2020-07-06 17:05:33 -0500

Hi everyone, first time posting.

My question relates to my attempt at creating a custom robot from scratch and trying to control it using MoveIt. I reverse engineered a model for an existing toy robot here. I also modify the arm to include encoders which are read by a Particle Photon micro and feed into my ROS controller node via RS232. I would post my URDF but i cant attach files yet, it took many hours to design the robot using SolidWorks and its URDF exporter (Note: pretty cool program)

I followed this example to get my arm working, I can send joint position targets using this command

~/catkin_ws$ rostopic pub /myrobot/joint_1/command std_msgs/Float64 -- -0.2

The above successfully drives joint 1 to the required angle.

/myrobot/launch/robot_position_controllers.launch

<?xml version="1.0"?>
<launch>
  <rosparam file="$(find myrobot)/config/hardware.yaml" command="load"/>
  <rosparam file="$(find myrobot)/config/ros_controllers.yaml" command="load"/>
  <rosparam file="$(find myrobot)/config/joint_limits.yaml" command="load"/>

  <param name="robot_description" textfile="$(find robotarm_individual)/urdf/robotarm_individual.urdf" />
  <node name="myrobot_node" pkg="myrobot" type="myrobot_node" output="screen" />
  <node name="robot_state_publisher" pkg="robot_state_publisher" type="robot_state_publisher" />
  <node name="controller_spawner" pkg="controller_manager" type="spawner" respawn="false" output="screen"
      args="joint_state_controller myrobot/joint_1 myrobot/joint_2 myrobot/joint_3 myrobot/joint_4 "/>
</launch>

/myrobot/config/hardward.yaml

myrobot:
  hardware_interface:
    loop_hz: 10 # hz
    joints:
      - jt1_joint
      - jt2_joint
      - jt3_joint
      - jt4_joint
      - jt5_joint

/myrobot/config/jointlimits.yaml

joint_limits:
  jt1_joint:
    has_position_limits: true
    min_position: -2.22
    max_position: 2.22
    has_velocity_limits: true
    max_velocity: 2.0
    has_acceleration_limits: true
    max_acceleration: 5.0
    has_jerk_limits: true
    max_jerk: 100.0
    has_effort_limits: true
    max_effort: 1.0
  jt2_joint:
    has_position_limits: true
    min_position: -0.84
    max_position: 1.84
    has_velocity_limits: true
    max_velocity: 2.0
    has_acceleration_limits: true
    max_acceleration: 5.0
    has_jerk_limits: true
    max_jerk: 100.0
    has_effort_limits: true
    max_effort: 1.0
  jt3_joint:
    has_position_limits: true
    min_position: -2.63
    max_position: 2.63
    has_velocity_limits: true
    max_velocity: 2.0
    has_acceleration_limits: true
    max_acceleration: 5.0
    has_jerk_limits: true
    max_jerk: 100.0
    has_effort_limits: true
    max_effort: 1.0
  jt4_joint:
    has_position_limits: true
    min_position: -0.6
    max_position: 0.6
    has_velocity_limits: true
    max_velocity: 2.0
    has_acceleration_limits: true
    max_acceleration: 5.0
    has_jerk_limits: true
    max_jerk: 100.0
    has_effort_limits: true
    max_effort: 1.0
  jt5_joint:
    has_position_limits: true
    min_position: 0
    max_position: 0.03
    has_velocity_limits: true
    max_velocity: 2.0
    has_acceleration_limits: true
    max_acceleration: 5.0
    has_jerk_limits: true
    max_jerk: 100.0
    has_effort_limits: true
    max_effort: 1.0

/myrobot/config/ros_contollers.yaml

# Publish all joint states
# Creates the /joint_states topic necessary in ROS
joint_state_controller:
  type: joint_state_controller/JointStateController
  publish_rate: 50

controller_list:
[]
myrobot:
  joint_1:
    type: position_controllers/JointPositionController
    joint: jt1_joint

  joint_2:
    type: position_controllers/JointPositionController
    joint: jt2_joint

  joint_3:
    type: position_controllers/JointPositionController
    joint: jt3_joint

  joint_4:
    type: position_controllers/JointPositionController
    joint: jt4_joint

The problem is, from what i can gather, MoveIt requires a group of joints, not individual joints

Following this tutorial MoveIt setup assistant I created a MoveIt configuration. This tutorial asks to specify the Planning Group, which is created including the 4 joints related to the arm part, the gripper is joint5. A note about 4DOF, I found that if i add "position_only_ik: True" to the kinematics.yaml ... (more)

edit retag flag offensive close merge delete

1 Answer

Sort by ยป oldest newest most voted
0

answered 2020-07-05 04:23:31 -0500

gvdhoorn gravatar image

updated 2020-07-07 02:31:17 -0500

You'll want to add a JointTrajectoryController to your ros_control configuration.

Something like this should work:

pos_joint_traj_controller:
  type: position_controllers/JointTrajectoryController
  joints:
    - jt1_joint
    - jt2_joint
    - jt3_joint
    - jt4_joint
    - jt5_joint
  constraints:
    goal_time: 0.6
    stopped_velocity_tolerance: 0.05
    jt1_joint: {trajectory: 0.2, goal: 0.1}
    jt2_joint: {trajectory: 0.2, goal: 0.1}
    jt3_joint: {trajectory: 0.2, goal: 0.1}
    jt4_joint: {trajectory: 0.2, goal: 0.1}
    jt5_joint: {trajectory: 0.2, goal: 0.1}
  stop_trajectory_duration: 0.5
  state_publish_rate: 25
  action_monitor_rate: 10

Note: the constraints section could require some tweaking to get the values right for your robot.

In general being able to control individual joints is nice, but typically I don't really have a use-case for it.

To me a JointGroupPositionController would make more sense, if you're not interested in executing trajectories.

edit flag offensive delete link more

Comments

Hi gvdhoorm, thanks heaps for your reply. I would love to add/make a JointTrajectoryController, but I can't find any code examples of how to do that. The examples i found only show position or effort controllers, one joint at a time :(

Zonared gravatar image Zonared  ( 2020-07-05 05:33:10 -0500 )edit

That's not how ros_control works.

As soon as you have a hardware_interface implemented -- which you have, or otherwise you could not have used those individual position_controllers/JointPositionControllers -- you can use all the controllers available in ros_control.

Provided of course that you use the correct version (ie: only use position_controllers if your hardware_interface only exposes PositionJointInterfaces for your joints, etc).

I would love to add/make a JointTrajectoryController, but I can't find any code examples of how to do that

which would make sense, as there is nothing "special" to do.

gvdhoorn gravatar image gvdhoorn  ( 2020-07-05 06:11:03 -0500 )edit

Ok, thanks again for your info. So does it come down to configuration and settings then? How do I combine all my individual controllers into a group that Moveit can use?

Zonared gravatar image Zonared  ( 2020-07-05 06:41:39 -0500 )edit

That's what I show in my answer.

You configure the JointTrajectoryController to be loaded onto your hardware_interface and then configure MoveIt to use that controller.

But to verify things work I would suggest to first play around a bit with the rqt_joint_trajectory_controller.

gvdhoorn gravatar image gvdhoorn  ( 2020-07-05 06:42:52 -0500 )edit

Right-o, I will have to sit down and configure your suggestion. Again, thanks heaps for your assistance. I'll report back as soon as I get a chance to play.

Zonared gravatar image Zonared  ( 2020-07-05 07:03:40 -0500 )edit

Thanks again for your help, you were indeed correct. It works as expected! I added this to the bottom of my ros_controllers.yaml file:

jc4dof:
  type: position_controllers/JointTrajectoryController
  joints:
    - jt1_joint
    - jt2_joint
    - jt3_joint
    - jt4_joint
  constraints:
    goal_time: 2.0
    stopped_velocity_tolerance: 0.1
    jt1_joint: {trajectory: 0.2, goal: 0.1}
    jt2_joint: {trajectory: 0.2, goal: 0.1}
    jt3_joint: {trajectory: 0.2, goal: 0.1}
    jt4_joint: {trajectory: 0.2, goal: 0.1}
  stop_trajectory_duration: 0.5
  state_publish_rate: 25
  action_monitor_rate: 10

I did have to modify by URDF to include a non zero valve for velocity="0.5", if this was zero rqt_joint_trajectory_controller produced the following (only include just in case some else comes across this) dur.append(max(abs(cmd - pos) / max_vel, self._min_traj_dur)) ZeroDivisionError: float division by zero

Much appreciate

Zonared gravatar image Zonared  ( 2020-07-06 16:59:20 -0500 )edit

Question Tools

2 followers

Stats

Asked: 2020-07-04 21:40:35 -0500

Seen: 814 times

Last updated: Jul 07 '20