Broken moveit_commander c++

This commit is contained in:
John Farrell 2022-02-15 22:21:15 -05:00
parent 215bfa2dc2
commit c478876ecf
Signed by: john
GPG key ID: 10543A0DA2EC1E12
4 changed files with 129 additions and 0 deletions

View file

@ -0,0 +1,48 @@
cmake_minimum_required(VERSION 3.5)
project(action_server)
# Default to C99
if(NOT CMAKE_C_STANDARD)
set(CMAKE_C_STANDARD 99)
endif()
# Default to C++14
if(NOT CMAKE_CXX_STANDARD)
set(CMAKE_CXX_STANDARD 14)
endif()
if(CMAKE_COMPILER_IS_GNUCXX OR CMAKE_CXX_COMPILER_ID MATCHES "Clang")
add_compile_options(-Wall -Wextra -Wpedantic)
endif()
# find dependencies
find_package(ament_cmake REQUIRED)
find_package(rclcpp REQUIRED)
find_package(geometry_msgs REQUIRED)
# uncomment the following section in order to fill in
# further dependencies manually.
# find_package(<dependency> REQUIRED)
add_executable(action_server src/action_server.cpp)
target_include_directories(action_server PUBLIC
$<BUILD_INTERFACE:${CMAKE_CURRENT_SOURCE_DIR}/include>
$<INSTALL_INTERFACE:include>)
ament_target_dependencies(action_server rclcpp geometry_msgs)
install(TARGETS action_server
DESTINATION lib/${PROJECT_NAME})
if(BUILD_TESTING)
find_package(ament_lint_auto REQUIRED)
# the following line skips the linter which checks for copyrights
# uncomment the line when a copyright and license is not present in all source files
#set(ament_cmake_copyright_FOUND TRUE)
# the following line skips cpplint (only works in a git repo)
# uncomment the line when this package is not in a git repo
#set(ament_cmake_cpplint_FOUND TRUE)
ament_lint_auto_find_test_dependencies()
endif()
ament_package()

View file

@ -0,0 +1,20 @@
#include "rclcpp/rclcpp.hpp"
#include "geometry_msgs/msg/pose.hpp"
#include <string>
class ActionServer : public rclcpp::Node {
public:
ActionServer();
private:
void set_pose_cb(geometry_msgs::msg::Pose);
private:
rclcpp::Node::SharedPtr _move_group_node;
rclcpp::Subscription<geometry_msgs::msg::Pose> _goal;
const std::string PLANNING_GROUP = "ar3_arm";
};

View file

@ -0,0 +1,21 @@
<?xml version="1.0"?>
<?xml-model href="http://download.ros.org/schema/package_format3.xsd" schematypens="http://www.w3.org/2001/XMLSchema"?>
<package format="3">
<name>action_server</name>
<version>1.0.0</version>
<description>Server for handling absolute movements</description>
<maintainer email="tmuller2017@my.fit.edu">Thomas Muller</maintainer>
<maintainer email="farrell2017@my.fit.edu">John Farrell</maintainer>
<license>TODO: License declaration</license>
<buildtool_depend>ament_cmake</buildtool_depend>
<depend>rclcpp</depend>
<depend>geometry_msgs</depend>
<test_depend>ament_lint_auto</test_depend>
<test_depend>ament_lint_common</test_depend>
<export>
<build_type>ament_cmake</build_type>
</export>
</package>

View file

@ -0,0 +1,40 @@
// https://github.com/ros-planning/moveit2_tutorials/blob/foxy/doc/move_group_interface/src/move_group_interface_tutorial.cpp
// maybe use this: https://github.com/ros-planning/moveit2/issues/775
#include <action_server/action_server.hpp>
#include <moveit/move_group_interface/move_group_interface.h>
ActionServer::ActionServer() : rclcpp::Node("action_server") {
// Get the move_group we'll apply transformations to
moveit::planning_interface::MoveGroupInterface move_group(ActionServer::_move_group_node, PLANNING_GROUP);
// Define the planning scene
moveit::planning_interface::PlanningSceneInterface planning_scene_interface;
// Define a pointer to the planning scene because tutorial says it's faster
const moveit::core::JointModelGroup* joint_model_group = move_group.getCurrentState()->getJointModelGroup(ActionServer::PLANNING_GROUP);
// Set up the callback for settings the pose from camera/joystick/etc
ActionServer::_goal = _move_group_node->create_subscription<geometry_msgs::msg::Pose>("/set_pose", 10, std::bind(&ActionServer::set_pose_cb, this, std::placeholders::_1));
}
void set_pose_cb(geometry_msgs::msg::Pose::SharedPtr pose) {
move_group.setPoseTarget(pose);
// plan the trajectory for the move
moveit::planning_interface::MoveGroupInterface::Plan my_plan;
bool success = (move_group.plan(my_plan) == moveit::planning_interface::MoveItErrorCode::SUCCESS);
move_group.move();
}
int main(int argc, char **argv) {
rclcpp::init(argc, argv);
_move_group_node = std::make_shared<ActionServer>();
rclcpp::spin(move_group_node);
rclcpp::shutdown();
return 0;
}