From e5e8110697a3e241f89dec91aad2d05d5c2fb382 Mon Sep 17 00:00:00 2001 From: Bill Finger Date: Sat, 30 Dec 2023 14:31:01 +0300 Subject: [PATCH] load default enviroment --- .../env_manager/src/run_env_manager.cpp | 4 ++-- .../action/MoveitSendPoses.action | 23 +++++++++++++++++++ 2 files changed, 25 insertions(+), 2 deletions(-) create mode 100644 rbs_skill_interfaces/action/MoveitSendPoses.action diff --git a/env_manager/env_manager/src/run_env_manager.cpp b/env_manager/env_manager/src/run_env_manager.cpp index fa5d15b..1506122 100644 --- a/env_manager/env_manager/src/run_env_manager.cpp +++ b/env_manager/env_manager/src/run_env_manager.cpp @@ -11,8 +11,8 @@ int main(int argc, char** argv) RCLCPP_INFO(em->get_logger(), "Env manager is starting"); - // em->loadEnv("gz_enviroment", "gz_enviroment::GzEnviroment"); - // em->configureEnv("gz_enviroment"); + em->loadEnv("gz_enviroment", "gz_enviroment::GzEnviroment"); + em->configureEnv("gz_enviroment"); executor->add_node(em); executor->spin(); diff --git a/rbs_skill_interfaces/action/MoveitSendPoses.action b/rbs_skill_interfaces/action/MoveitSendPoses.action new file mode 100644 index 0000000..4ff8fa8 --- /dev/null +++ b/rbs_skill_interfaces/action/MoveitSendPoses.action @@ -0,0 +1,23 @@ +##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/Pose[] 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 +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