many changes

This commit is contained in:
Ilya Uraev 2022-01-31 21:28:39 +04:00
parent 0f172f6f4b
commit 7322505b1e
23 changed files with 499 additions and 70 deletions

View file

@ -0,0 +1,33 @@
cmake_minimum_required(VERSION 3.5)
project(robossembler_interfaces)
# 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(rosidl_default_generators REQUIRED)
rosidl_generate_interfaces(${PROJECT_NAME}
"action/MoveitSendPose.action"
"msg/ActionFeedbackStatusConstants.msg"
"msg/ActionResultStatusConstants.msg"
)
if(BUILD_TESTING)
find_package(ament_lint_auto REQUIRED)
ament_lint_auto_find_test_dependencies()
endif()
ament_package()

View file

@ -0,0 +1,17 @@
##Description: Moves robot arm to a specified joint space.
#goal definition
moveit_action_handlers/PropertyValuePair[] joint_pairs # list of joint_pairs (joint name + value)
float32 end_effector_velocity
float32 end_effector_acceleration
float32 timeout_seconds #if this action cannot be completed within this time period it should be considered failed.
---
#result definition
bool success
uint64 millis_passed
string status #Use the constants of ActionResultStatusConstants in the status field
---
#feedback
bool success
uint64 millis_passed
string status #Use the constants of ActionFeedbackStatusConstants in the status field

View file

@ -0,0 +1,24 @@
##Description: Moves robot arm to a specified pose relative to the frame in header.frame_id of target_pose
#goal definition
#Used to indicate which hardcoded motion constraint to use
#e.g 0 no constraint, 1 keep the same end effector orientation
int32 constraint_mode
#similar to geometry_msgs/PoseStamped but using euler instead of quaternion
#at target_pose->header.frame_id define the tf frame
# which the pose will be calculated relative from
geometry_msgs/PoseStamped target_pose
string robot_name
float32 end_effector_velocity
float32 end_effector_acceleration
float32 timeout_seconds #if this action cannot be completed within this time period it should be considered failed.
---
#result definition
bool success
uint64 millis_passed
string status #Use the constants of ActionResultStatusConstants in the status field
---
#feedback
bool success
uint64 millis_passed
string status #Use the constants of ActionFeedbackStatusConstants in the status field

View file

@ -0,0 +1,5 @@
string PLANNING="Planning"
string EXECUTING="Executing"
string EMERGENCY_STOP="EmergencyStop"
string OPERATIONAL_EXCEPTION="OperationalException"
string CANCELLING="Cancelling"

View file

@ -0,0 +1,6 @@
string SUCCESS="Success"
string PLANNING_FAILED="PlanningFailed"
string CONTROL_FAILED="ControlFailed"
string EMERGENCY_STOP="EmergencyStop"
string OPERATIONAL_EXCEPTION="OperationalException"
string CANCELLED="Cancelled"

View file

@ -0,0 +1,5 @@
##Usage: In MoveToJointsMoveIt.action
##Definition: A property name - Value definition.
string name
float64 value

View file

@ -0,0 +1,23 @@
<?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>robossembler_interfaces</name>
<version>0.0.0</version>
<description>TODO: Package description</description>
<maintainer email="ur.narmak@gmail.com">bill-finger</maintainer>
<license>TODO: License declaration</license>
<buildtool_depend>ament_cmake</buildtool_depend>
<build_depend>rosidl_default_generators</build_depend>
<exec_depend>rosidl_default_runtime</exec_depend>
<test_depend>ament_lint_auto</test_depend>
<test_depend>ament_lint_common</test_depend>
<member_of_group>rosidl_interface_packages</member_of_group>
<export>
<build_type>ament_cmake</build_type>
</export>
</package>