########################################################## Control Ned/Ned2 with MoveIt and ROS Multi-Machines ########################################################## **V.1.1** .. image:: /images/moveit_multimachines/niryo_moveit_multimachines.png :alt: Niryo Moveit! multimachines banner :width: 100% :align: center Difficulty: ``easy`` Time: ``~10 min`` .. note:: This tutorial is working from: | The version v3.2.0 of the ned_ros_stack This tutorial explains how to control Ned/Ned2 with Rviz through the MoveIt plugin, in Multi-machines. Before going further, please refer to our :doc:`Multi-machines <./setup_ned_ros_multi_machines>`, and our :doc:`Connect to Ned via SSH <./setup_connect_ned_ssh>` tutorials. You can also refer to the ROS Multi-machines tutorial: `Running ROS across multiple machines `_. What you will need ------------------------- - A Ned (or a Ned2), - A computer with Ubuntu (we used Ubuntu 18.04), - To have Rviz installed on your computer, - To have the niryo_robot_bringup ROS package on your computer, a part of the Ned/Ned2 ROS Stack that you can `download here `_. Setup ------------------------- In each terminal you'll use, you have to setup the ROS_MASTER_URI and ROS_IP environment variables. **The master is hosted on Ned/Ned2**. .. hint:: We recommend to use an ethernet connection between your computer and Ned to optimize the communication speed. On Ned/Ned2 ^^^^^^^^^^^ First, in a terminal, connect to Ned/Ned2 in SSH, with the command line: :: ssh niryo@ We use the **hardware_interface_standalone.launch** file, which only launches on Ned/Ned2: - The Hardware Stack (which publishes on the /joint_state topic), with the motor's drivers, - The controllers, - The robot description (loads the urdf file of the robot), - The robot state publisher. Launch it on Ned/Ned2 with: :: roslaunch niryo_robot_hardware_interface hardware_interface_standalone.launch On your computer ^^^^^^^^^^^^^^^^^^ We use the **moveit_multimachines.launch** file, which launches: - The command validation group (which checks that commands are not out of bounds) - The Moveit! move group interface This file is in the niryo_robot_bringup package on the Ned/Ned2 ROS Stack. Launch it with: :: roslaunch niryo_robot_bringup moveit_multimachines.launch Finally, in a third terminal, launch **Rviz** with: :: rosrun rviz rviz Control Ned/Ned2 through Rviz ------------------------------------- After opening Rviz, make sure that the "fixed frame" is set to "world". Add the **MotionPlanning** to the visualization. You should now have: .. figure :: ../../images/moveit_multimachines/rviz_visualization.png :width: 900px :align: center Ned in Rviz .. important:: In order to make Ned/Ned2 move, you'll have to: - Make sure Ned/Ned2 is well calibrated with: :: rosservice call /niryo_robot/joints_interface/calibrate_motors "value: 1" - Deactivate the Learning Mode with: :: rosservice call /niryo_robot/learning_mode/activate "value: false" You should now be able to move the goal position and orientation of the end effector thanks to the differents arrows: .. figure :: ../../images/moveit_multimachines/new_goal.png :width: 900px :align: center Define a new goal Once the goal position is defined, click **Plan and Execute** so Moveit! calculate the path to the goal and execute it. You are now able to visualize Ned/Ned2's current state in Rviz, and to control its movements through Rviz. .. figure :: ../../images/moveit_multimachines/plan_and_execute.png :width: 900px :align: center Plan and execute path You can also play with the **many options** provided by MotionPlanning, like making Ned/Ned2 move along a Cartesian path!