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

MATLAB integration with ROS for Cartesian Motion Planning using Moveit

asked 2016-03-30 22:04:11 -0500

umerhuzaifa gravatar image

updated 2016-03-31 02:50:20 -0500

gvdhoorn gravatar image

Hi,

I am interested in using MATLAB Robotics Systems Toolbox (RST) to use Moveit in ROS for planning and executing Cartesian Trajectories. I have checked the RViz interface of Moveit in ROS only. I have checked the C++ tutorials for Moveit (which are not as clear as they could be) but I am still not able to pass the desired cartesian paths to ROS. In MATLAB RST, I can only use some services or publish messages to nodes related to target pose planning and executing but I can not figure out what they are.

As an example, I have a 7DOF arm available in ROS with working Moveit in RViz interface.

I can see following topics that I can talk to in MATLAB:

/attached_collision_object
/clock
/collision_object
/gazebo/link_states
/gazebo/model_states
/gazebo/parameter_descriptions
/gazebo/parameter_updates
/gazebo/set_link_state
/gazebo/set_model_state
/joint_states
/move_group/cancel
/move_group/display_contacts
/move_group/display_planned_path
/move_group/feedback
/move_group/goal
/move_group/monitored_planning_scene
/move_group/ompl/parameter_descriptions
/move_group/ompl/parameter_updates
/move_group/plan_execution/parameter_descriptions
/move_group/plan_execution/parameter_updates
/move_group/planning_scene_monitor/parameter_descriptions
/move_group/planning_scene_monitor/parameter_updates
/move_group/result
/move_group/sense_for_plan/parameter_descriptions
/move_group/sense_for_plan/parameter_updates
/move_group/status
/move_group/trajectory_execution/parameter_descriptions
/move_group/trajectory_execution/parameter_updates
/pickup/cancel
/pickup/feedback
/pickup/goal
/pickup/result
/pickup/status
/place/cancel
/place/feedback
/place/goal
/place/result
/place/status
/planning_scene
/planning_scene_world
/recognized_object_array
/rgbd_camera/depth/camera_info
/rgbd_camera/depth/image_raw
/rgbd_camera/depth/points
/rgbd_camera/ir/camera_info
/rgbd_camera/ir/image_raw
/rgbd_camera/ir/image_raw/compressed
/rgbd_camera/ir/image_raw/compressed/parameter_descriptions
/rgbd_camera/ir/image_raw/compressed/parameter_updates
/rgbd_camera/ir/image_raw/compressedDepth
/rgbd_camera/ir/image_raw/compressedDepth/parameter_descriptions
/rgbd_camera/ir/image_raw/compressedDepth/parameter_updates
/rgbd_camera/ir/image_raw/theora
/rgbd_camera/ir/image_raw/theora/parameter_descriptions
/rgbd_camera/ir/image_raw/theora/parameter_updates
/rgbd_camera/parameter_descriptions
/rgbd_camera/parameter_updates
/rgbd_camera/rgb/camera_info
/rgbd_camera/rgb/image_raw
/rgbd_camera/rgb/image_raw/compressed
/rgbd_camera/rgb/image_raw/compressed/parameter_descriptions
/rgbd_camera/rgb/image_raw/compressed/parameter_updates
/rgbd_camera/rgb/image_raw/compressedDepth
/rgbd_camera/rgb/image_raw/compressedDepth/parameter_descriptions
/rgbd_camera/rgb/image_raw/compressedDepth/parameter_updates
/rgbd_camera/rgb/image_raw/theora
/rgbd_camera/rgb/image_raw/theora/parameter_descriptions
/rgbd_camera/rgb/image_raw/theora/parameter_updates
/rgbd_camera/rgb/points
/rosout
/rosout_agg
/rviz_RADLab_PC_27799_716056535572644738/motionplanning_planning_scene_monitor/parameter_descriptions /rviz_RADLab_PC_27799_716056535572644738/motionplanning_planning_scene_monitor/parameter_updates
/rviz_moveit_motion_planning_display/robot_interaction_interactive_marker_topic/feedback
/rviz_moveit_motion_planning_display/robot_interaction_interactive_marker_topic/update
/rviz_moveit_motion_planning_display/robot_interaction_interactive_marker_topic/update_full
/seven_dof_arm/gripper_controller/command
/seven_dof_arm/gripper_controller/follow_joint_trajectory/cancel
/seven_dof_arm/gripper_controller/follow_joint_trajectory/feedback
/seven_dof_arm/gripper_controller/follow_joint_trajectory/goal
/seven_dof_arm/gripper_controller/follow_joint_trajectory/result
/seven_dof_arm/gripper_controller/follow_joint_trajectory/status
/seven_dof_arm/gripper_controller/state
/seven_dof_arm/joint_states
/seven_dof_arm/seven_dof_arm_joint_controller/command
/seven_dof_arm/seven_dof_arm_joint_controller/follow_joint_trajectory/cancel
/seven_dof_arm/seven_dof_arm_joint_controller/follow_joint_trajectory/feedback
/seven_dof_arm/seven_dof_arm_joint_controller/follow_joint_trajectory/goal
/seven_dof_arm/seven_dof_arm_joint_controller/follow_joint_trajectory/result
/seven_dof_arm/seven_dof_arm_joint_controller/follow_joint_trajectory/status
/seven_dof_arm/seven_dof_arm_joint_controller/state
/tf
/tf_static
/trajectory_execution_event

What topics should I publish to?

Has anybody tried this in MATLAB? I know these solutions are available in Python and C++ but I dont want to leave MATLAB because all my algorithms are in m-codes.

Thanks

edit retag flag offensive close merge delete

Comments

Hi,

It is indeed an old post but I am currently stuck in trying to achieve the same as posted in the question above. I have went upto some extent and I have managed to send trajectory commands but from an m-file (following the PR2 robot example in Matlab for moving arms and that in joint space). But I am struggling with implementing the same from Robotics System Toolbox message and publish blocks.

Any help would be highly appreciated.

Thanks

gaz_prog gravatar image gaz_prog  ( 2021-03-19 05:14:58 -0500 )edit

1 Answer

Sort by ยป oldest newest most voted
3

answered 2016-04-01 01:43:13 -0500

Hamd ul Moqeet gravatar image

I have worked with Robotics Systems toolbox and ROS enabled robots like PhantomX pincher Arm. To find which topics you need to publish to, you can use 'rqt_graph' to figure out. I can only predict the topics. It seems like you have a few action servers running namely seven_dof_arm_joint_controller, gripper_controller, pickup, place, move_group. Action Servers take the goal as an input and output the status or feedback continuously. You can publish to the following topics (my guess only):

/move_group/goal

/pickup/goal

/place/goal

/seven_dof_arm/gripper_controller/command

/seven_dof_arm/gripper_controller/follow_joint_trajectory/goal

/seven_dof_arm/seven_dof_arm_joint_controller/command

/seven_dof_arm/seven_dof_arm_joint_controller/follow_joint_trajectory/goal

To simply move the robot in Joint space you can use topic '/seven_dof_arm/seven_dof_arm_joint_controller/command'. you first have to know the message type of this topic which can be extracted from using the following command in ubuntu terminal: rostopic info /seven_dof_arm/seven_dof_arm_joint_controller/command

once you know the message type you can search for message types documentation on wiki ros page or use 'rosmsg info' in terminal. This is necessary because we need to publish correct type of data structure to the topic, otherwise it wont work. If its a standard message type then you can ignore the details and things become easy. In the simplest case, you must publish the 7 joint variables (angles/d) in radians or meters as a vector(1x7).

You can also publish a complete Joint trajectory on the topic: /seven_dof_arm/seven_dof_arm_joint_controller/follow_joint_trajectory/goal Follow the same procedure as explained above. The following link might be helpful: http://wiki.ros.org/joint_trajectory_... http://docs.ros.org/api/trajectory_ms...

To Move the robot in Cartesian space, you can calculate the inverse kinematics in matlab first and then publish the joint angles. I cannot predict which topics need to published to.

In matlab you simply have to initialize to a ros network using rosinit. Then make a publisher object and message object and publish on the topic.

edit flag offensive delete link more

Question Tools

3 followers

Stats

Asked: 2016-03-30 21:59:31 -0500

Seen: 1,478 times

Last updated: Mar 30 '16