jrosmoveit is a Java module which allows to interact with MoveIt in ROS (Robot Operating System). It allows to set target pose for the robot, plan trajectory and execute it.
With jrosmoveit users can interact with MoveIt remotely from Java and manipulate variety of robotic arms. Neither ROS or MoveIt are required to be locally present.
jrosmoveit is based on jrosclient module which is a Java client for ROS.
In the following examples we will move Panda robotic arm.
Once code is executed the arm will move from its initial position to the point coordinates we specified.
Install MoveIt with Panda:
Use following commands to run it:
Java code:
import id.jros2client.*; import id.jrosmessages.geometry_msgs.*; import pinorobotics.jros2moveit.*; import pinorobotics.robotstate.*; var configBuilder = new JRos2ClientConfiguration.Builder(); // use configBuilder to override default parameters if needed try (var client = new JRos2ClientFactory().createClient(configBuilder.build());) { var moveIt = new JRos2MoveItFactory(). createMoveItClient(client, "panda_arm", new RobotModel("world")); var targetPose = new PoseMessage(). withPosition(new PointMessage(0.28, -0.2, 0.5)). withQuaternion(new QuaternionMessage().withW(-1.0)); moveIt.setPoseTarget(targetPose, "panda_hand"); var plan = moveIt.plan(); System.out.println("Calculated plan: " + plan); moveIt.execute(plan); }
Install Panda:
Use following commands to run it:
If it fails apply the fix.
Java code:
import id.jros1client.*; import id.jrosmessages.geometry_msgs.*; import pinorobotics.jros1moveit.*; import pinorobotics.robotstate.*; try (var client = new JRos1ClientFactory().createClient("http://localhost:11311/"); ) { var moveIt = new JRos1MoveItFactory(). createMoveItClient(client, "panda_arm", new RobotModel("world")); var targetPose = new PoseMessage(). withPosition(new PointMessage(0.28, -0.2, 0.5)). withQuaternion(new QuaternionMessage().withW(-1.0)); moveIt.setPoseTarget(targetPose, "panda_hand"); var plan = moveIt.plan(); System.out.println("Calculated plan: " + plan); moveIt.execute(plan); }