- Removed `assembly_config_service.py` node from launch configuration. - Added default `goal.duration` setting to `MoveToPose` and `MoveToPoseArray`. - Replaced `timeout_seconds` with `duration` in action definitions for `MoveitSendJointStates` and `MoveitSendPose`. - Removed dependencies on TinyXML2 and Gazebo/SDFormat, adding `controller_manager_msgs` and `control_msgs` to CMake configuration. - Added new action servers `cartesian_move_to_pose` and `move_to_joint_states`, registering them in CMakeLists file. - Introduced `SkillBase`, a template class for managing action-based skills, providing essential ROS 2 action server support and functionalities for handling goals, cancels, accepted actions, and controller management. - Implemented methods to load, configure, and switch required controllers with conflict detection for active controllers, along with parameter checking and asynchronous handling for required parameters. - Enhanced error handling for missing controllers, parameters, and resource conflicts. - Updated `skills.launch.py` to utilize `ComposableNodeContainer` for skill nodes, incorporating `MoveToJointStateActionServer` and `CartesianMoveToPose` as composable nodes. - Changed the executable name in `cartesian_move_to_pose_action_server` node configuration. - Added `cartesian_move_to_pose.cpp`, implementing the `CartesianMoveToPose` action server, including trajectory interpolation, pose adjustment, and controller management. - Updated `package.xml` to include `rclcpp_components` dependency. - Refactored `MoveToJointStateActionServer` to extend `SkillBase`, leveraging `FollowJointTrajectory` for joint trajectory execution, while removing redundant code and dependencies. - Implemented trajectory generation based on initial and target joint positions with parameterized interpolation for smoother execution, enhancing joint state handling to dynamically align current and target joint values.
24 lines
949 B
Text
24 lines
949 B
Text
##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 duration #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
|