Skip to content

Commit

Permalink
Created initial code to control UR10e movement via MoveIt! API (MoveG…
Browse files Browse the repository at this point in the history
…roup)
  • Loading branch information
willnatsan committed Jun 5, 2024
1 parent 1840263 commit 9eff013
Show file tree
Hide file tree
Showing 2 changed files with 342 additions and 10 deletions.
52 changes: 45 additions & 7 deletions ur10e_control/src/csv_control.cpp
Original file line number Diff line number Diff line change
@@ -1,10 +1,48 @@
#include <cstdio>
#include <memory>
#include <moveit/move_group_interface/move_group_interface.h>
#include <rclcpp/rclcpp.hpp>

int main(int argc, char ** argv)
{
(void) argc;
(void) argv;
int main(int argc, char *argv[]) {
// Initialize ROS and create the Node
rclcpp::init(argc, argv);
auto const node = std::make_shared<rclcpp::Node>(
"csv_control",
rclcpp::NodeOptions().automatically_declare_parameters_from_overrides(
true));

printf("hello world ur10e_control package\n");
// Create a ROS logger
auto const logger = rclcpp::get_logger("csv_control");

// Create the MoveIt MoveGroup Interface
using moveit::planning_interface::MoveGroupInterface;
auto move_group_interface = MoveGroupInterface(node, "ur10e_arm");

// Set a target Pose
auto const target_pose = [] {
geometry_msgs::msg::Pose msg;
msg.orientation.w = 1.0;
msg.position.x = 0.28;
msg.position.y = -0.2;
msg.position.z = 0.5;
return msg;
}();
move_group_interface.setPoseTarget(target_pose);

// Create a plan to that target pose
auto const [success, plan] = [&move_group_interface] {
moveit::planning_interface::MoveGroupInterface::Plan msg;
auto const ok = static_cast<bool>(move_group_interface.plan(msg));
return std::make_pair(ok, msg);
}();

// Execute the plan
if (success) {
move_group_interface.execute(plan);
} else {
RCLCPP_ERROR(logger, "Planning failed!");
}

// Shutdown ROS
rclcpp::shutdown();
return 0;
}
}
300 changes: 297 additions & 3 deletions ur10e_description/rviz/view_robot.rviz
Original file line number Diff line number Diff line change
Expand Up @@ -7,7 +7,7 @@ Panels:
- /Global Options1
- /Status1
Splitter Ratio: 0.5
Tree Height: 701
Tree Height: 364
- Class: rviz_common/Selection
Name: Selection
- Class: rviz_common/Tool Properties
Expand Down Expand Up @@ -177,6 +177,296 @@ Visualization Manager:
Update Interval: 0
Value: true
Visual Enabled: true
- Acceleration_Scaling_Factor: 0.1
Class: moveit_rviz_plugin/MotionPlanning
Enabled: true
Move Group Namespace: ""
MoveIt_Allow_Approximate_IK: false
MoveIt_Allow_External_Program: false
MoveIt_Allow_Replanning: false
MoveIt_Allow_Sensor_Positioning: false
MoveIt_Planning_Attempts: 10
MoveIt_Planning_Time: 5
MoveIt_Use_Cartesian_Path: false
MoveIt_Use_Constraint_Aware_IK: false
MoveIt_Workspace:
Center:
X: 0
Y: 0
Z: 0
Size:
X: 2
Y: 2
Z: 2
Name: MotionPlanning
Planned Path:
Color Enabled: false
Interrupt Display: false
Links:
All Links Enabled: true
Expand Joint Details: false
Expand Link Details: false
Expand Tree: false
Link Tree Style: Links in Alphabetic Order
robotiq_85_base_link:
Alpha: 1
Show Axes: false
Show Trail: false
Value: true
robotiq_85_left_finger_link:
Alpha: 1
Show Axes: false
Show Trail: false
Value: true
robotiq_85_left_finger_tip_link:
Alpha: 1
Show Axes: false
Show Trail: false
Value: true
robotiq_85_left_inner_knuckle_link:
Alpha: 1
Show Axes: false
Show Trail: false
Value: true
robotiq_85_left_knuckle_link:
Alpha: 1
Show Axes: false
Show Trail: false
Value: true
robotiq_85_right_finger_link:
Alpha: 1
Show Axes: false
Show Trail: false
Value: true
robotiq_85_right_finger_tip_link:
Alpha: 1
Show Axes: false
Show Trail: false
Value: true
robotiq_85_right_inner_knuckle_link:
Alpha: 1
Show Axes: false
Show Trail: false
Value: true
robotiq_85_right_knuckle_link:
Alpha: 1
Show Axes: false
Show Trail: false
Value: true
ur10e_base:
Alpha: 1
Show Axes: false
Show Trail: false
ur10e_base_link:
Alpha: 1
Show Axes: false
Show Trail: false
ur10e_base_link_inertia:
Alpha: 1
Show Axes: false
Show Trail: false
Value: true
ur10e_flange:
Alpha: 1
Show Axes: false
Show Trail: false
ur10e_forearm_link:
Alpha: 1
Show Axes: false
Show Trail: false
Value: true
ur10e_ft_frame:
Alpha: 1
Show Axes: false
Show Trail: false
ur10e_shoulder_link:
Alpha: 1
Show Axes: false
Show Trail: false
Value: true
ur10e_tool0:
Alpha: 1
Show Axes: false
Show Trail: false
ur10e_upper_arm_link:
Alpha: 1
Show Axes: false
Show Trail: false
Value: true
ur10e_wrist_1_link:
Alpha: 1
Show Axes: false
Show Trail: false
Value: true
ur10e_wrist_2_link:
Alpha: 1
Show Axes: false
Show Trail: false
Value: true
ur10e_wrist_3_link:
Alpha: 1
Show Axes: false
Show Trail: false
Value: true
world:
Alpha: 1
Show Axes: false
Show Trail: false
Loop Animation: false
Robot Alpha: 0.5
Robot Color: 150; 50; 150
Show Robot Collision: false
Show Robot Visual: true
Show Trail: false
State Display Time: 3x
Trail Step Size: 1
Trajectory Topic: /display_planned_path
Use Sim Time: false
Planning Metrics:
Payload: 1
Show Joint Torques: false
Show Manipulability: false
Show Manipulability Index: false
Show Weight Limit: false
TextHeight: 0.07999999821186066
Planning Request:
Colliding Link Color: 255; 0; 0
Goal State Alpha: 1
Goal State Color: 250; 128; 0
Interactive Marker Size: 0
Joint Violation Color: 255; 0; 255
Planning Group: ur10e_arm
Query Goal State: true
Query Start State: false
Show Workspace: false
Start State Alpha: 1
Start State Color: 0; 255; 0
Planning Scene Topic: /monitored_planning_scene
Robot Description: robot_description
Scene Geometry:
Scene Alpha: 0.8999999761581421
Scene Color: 50; 230; 50
Scene Display Time: 0.009999999776482582
Show Scene Geometry: true
Voxel Coloring: Z-Axis
Voxel Rendering: Occupied Voxels
Scene Robot:
Attached Body Color: 150; 50; 150
Links:
All Links Enabled: true
Expand Joint Details: false
Expand Link Details: false
Expand Tree: false
Link Tree Style: Links in Alphabetic Order
robotiq_85_base_link:
Alpha: 1
Show Axes: false
Show Trail: false
Value: true
robotiq_85_left_finger_link:
Alpha: 1
Show Axes: false
Show Trail: false
Value: true
robotiq_85_left_finger_tip_link:
Alpha: 1
Show Axes: false
Show Trail: false
Value: true
robotiq_85_left_inner_knuckle_link:
Alpha: 1
Show Axes: false
Show Trail: false
Value: true
robotiq_85_left_knuckle_link:
Alpha: 1
Show Axes: false
Show Trail: false
Value: true
robotiq_85_right_finger_link:
Alpha: 1
Show Axes: false
Show Trail: false
Value: true
robotiq_85_right_finger_tip_link:
Alpha: 1
Show Axes: false
Show Trail: false
Value: true
robotiq_85_right_inner_knuckle_link:
Alpha: 1
Show Axes: false
Show Trail: false
Value: true
robotiq_85_right_knuckle_link:
Alpha: 1
Show Axes: false
Show Trail: false
Value: true
ur10e_base:
Alpha: 1
Show Axes: false
Show Trail: false
ur10e_base_link:
Alpha: 1
Show Axes: false
Show Trail: false
ur10e_base_link_inertia:
Alpha: 1
Show Axes: false
Show Trail: false
Value: true
ur10e_flange:
Alpha: 1
Show Axes: false
Show Trail: false
ur10e_forearm_link:
Alpha: 1
Show Axes: false
Show Trail: false
Value: true
ur10e_ft_frame:
Alpha: 1
Show Axes: false
Show Trail: false
ur10e_shoulder_link:
Alpha: 1
Show Axes: false
Show Trail: false
Value: true
ur10e_tool0:
Alpha: 1
Show Axes: false
Show Trail: false
ur10e_upper_arm_link:
Alpha: 1
Show Axes: false
Show Trail: false
Value: true
ur10e_wrist_1_link:
Alpha: 1
Show Axes: false
Show Trail: false
Value: true
ur10e_wrist_2_link:
Alpha: 1
Show Axes: false
Show Trail: false
Value: true
ur10e_wrist_3_link:
Alpha: 1
Show Axes: false
Show Trail: false
Value: true
world:
Alpha: 1
Show Axes: false
Show Trail: false
Robot Alpha: 1
Show Robot Collision: false
Show Robot Visual: true
Value: true
Velocity_Scaling_Factor: 0.1
Enabled: true
Global Options:
Background Color: 48; 48; 48
Expand Down Expand Up @@ -244,12 +534,16 @@ Visualization Manager:
Yaw: 0.18041197955608368
Saved: ~
Window Geometry:
"":
collapsed: false
" - Trajectory Slider":
collapsed: false
Displays:
collapsed: false
Height: 1008
Height: 1080
Hide Left Dock: false
Hide Right Dock: false
QMainWindow State: 000000ff00000000fd00000004000000000000016a0000034ffc0200000008fb0000001200530065006c0065006300740069006f006e00000001e10000009b0000006300fffffffb0000001e0054006f006f006c002000500072006f007000650072007400690065007302000001ed000001df00000185000000a3fb000000120056006900650077007300200054006f006f02000001df000002110000018500000122fb000000200054006f006f006c002000500072006f0070006500720074006900650073003203000002880000011d000002210000017afb000000100044006900730070006c006100790073010000003e0000034f000000da00fffffffb0000002000730065006c0065006300740069006f006e00200062007500660066006500720200000138000000aa0000023a00000294fb00000014005700690064006500530074006500720065006f02000000e6000000d2000003ee0000030bfb0000000c004b0069006e0065006300740200000186000001060000030c00000261000000010000010f0000034ffc0200000003fb0000001e0054006f006f006c002000500072006f00700065007200740069006500730100000041000000780000000000000000fb0000000a00560069006500770073010000003e0000034f000000b100fffffffb0000001200530065006c0065006300740069006f006e010000025a000000b200000000000000000000000200000490000000a9fc0100000001fb0000000a00560069006500770073030000004e00000080000002e10000019700000003000007800000003efc0100000002fb0000000800540069006d0065010000000000000780000002d400fffffffb0000000800540069006d00650100000000000004500000000000000000000004fb0000034f00000004000000040000000800000008fc0000000100000002000000010000000a0054006f006f006c00730100000000ffffffff0000000000000000
QMainWindow State: 000000ff00000000fd0000000400000000000001ed00000394fc020000000afb0000001200530065006c0065006300740069006f006e00000001e10000009b0000006300fffffffb0000001e0054006f006f006c002000500072006f007000650072007400690065007302000001ed000001df00000185000000a3fb000000120056006900650077007300200054006f006f02000001df000002110000018500000122fb000000200054006f006f006c002000500072006f0070006500720074006900650073003203000002880000011d000002210000017afb000000100044006900730070006c006100790073010000003f000001ff000000db00fffffffb0000002000730065006c0065006300740069006f006e00200062007500660066006500720200000138000000aa0000023a00000294fb00000014005700690064006500530074006500720065006f02000000e6000000d2000003ee0000030bfb0000000c004b0069006e0065006300740200000186000001060000030c00000261fb000000280020002d0020005400720061006a006500630074006f0072007900200053006c00690064006500720000000000ffffffff0000004700fffffffbffffffff01000002440000018f0000017600ffffff000000010000010f00000394fc0200000003fb0000001e0054006f006f006c002000500072006f00700065007200740069006500730100000041000000780000000000000000fb0000000a00560069006500770073010000003f00000394000000b300fffffffb0000001200530065006c0065006300740069006f006e010000025a000000b200000000000000000000000200000490000000a9fc0100000001fb0000000a00560069006500770073030000004e00000080000002e10000019700000003000007800000003ffc0100000002fb0000000800540069006d0065010000000000000780000002fb00fffffffb0000000800540069006d00650100000000000004500000000000000000000004780000039400000004000000040000000800000008fc0000000100000002000000010000000a0054006f006f006c00730100000000ffffffff0000000000000000
Selection:
collapsed: false
Time:
Expand Down

0 comments on commit 9eff013

Please sign in to comment.