-
Notifications
You must be signed in to change notification settings - Fork 0
Commit
This commit does not belong to any branch on this repository, and may belong to a fork outside of the repository.
Created initial attempt of csv_control and moved working code to simp…
…le_control
- Loading branch information
1 parent
9eff013
commit f981909
Showing
2 changed files
with
125 additions
and
24 deletions.
There are no files selected for viewing
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
Original file line number | Diff line number | Diff line change |
---|---|---|
@@ -0,0 +1,48 @@ | ||
#include <memory> | ||
#include <moveit/move_group_interface/move_group_interface.h> | ||
#include <rclcpp/rclcpp.hpp> | ||
|
||
int main(int argc, char *argv[]) { | ||
// Initialize ROS and create the Node | ||
rclcpp::init(argc, argv); | ||
auto const node = std::make_shared<rclcpp::Node>( | ||
"simple_control", | ||
rclcpp::NodeOptions().automatically_declare_parameters_from_overrides( | ||
true)); | ||
|
||
// Create a ROS logger | ||
auto const logger = rclcpp::get_logger("simple_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; | ||
} |