Skip to content

Commit

Permalink
[Feat] (xarm_api) add some services
Browse files Browse the repository at this point in the history
  • Loading branch information
vimior committed Nov 14, 2022
1 parent fd9f6c8 commit a08120a
Show file tree
Hide file tree
Showing 20 changed files with 700 additions and 4 deletions.
3 changes: 2 additions & 1 deletion ReadMe.md
Original file line number Diff line number Diff line change
Expand Up @@ -21,7 +21,8 @@ For simplified Chinese version: [简体中文版](./ReadMe_cn.md)
- (2022-09-07) Change the parameter type of service (__set_tgpio_modbus_timeout__/__getset_tgpio_modbus_data__), and add parameters to support transparent transmission
- (2022-09-07) Change topic name (xarm_states to robot_states)
- (2022-09-07) Update submodule xarm-sdk to version 1.11.0
- (2022-09-09) [Beta]支持Ros Humble版本
- (2022-09-09) [Beta]Support Humble version
- (2022-10-10) xarm_api adds some services


## 3. Preparation
Expand Down
1 change: 1 addition & 0 deletions ReadMe_cn.md
Original file line number Diff line number Diff line change
Expand Up @@ -21,6 +21,7 @@
- (2022-09-07) 变更Topic名字(xarm_states改为robot_states)
- (2022-09-07) 更新子模块xarm-sdk到1.11.0版本
- (2022-09-09) [Beta]支持Ros Humble版本
- (2022-10-10) xarm_api新增一些服务

## 3. 准备工作

Expand Down
40 changes: 39 additions & 1 deletion xarm_api/config/xarm_params.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -23,13 +23,31 @@ ufactory_driver:
clean_bio_gripper_error: false
start_record_trajectory: false
stop_record_trajectory: false
ft_sensor_set_zero: false
set_linear_track_stop: false
clean_linear_track_error: false
open_lite6_gripper: false
close_lite6_gripper: false
stop_lite6_gripper: false
get_state: false
get_cmdnum: false
get_vacuum_gripper: false
get_gripper_err_code: false
get_bio_gripper_status: false
get_bio_gripper_error: false
get_reduced_mode: false
get_report_tau_or_i: false
ft_sensor_app_get: false
get_ft_sensor_error: false
get_trajectory_rw_status: false
get_linear_track_pos: false
get_linear_track_status: false
get_linear_track_error: false
get_linear_track_is_enabled: false
get_linear_track_on_zero: false
get_linear_track_sci: false
get_err_warn_code: false
get_linear_track_sco: false
set_mode: true
set_state: true
set_collision_sensitivity: false
Expand All @@ -44,6 +62,16 @@ ufactory_driver:
set_self_collision_detection: false
set_simulation_robot: false
set_baud_checkset_enable: false
set_report_tau_or_i: false
ft_sensor_enable: false
ft_sensor_app_set: false
set_linear_track_enable: false
set_linear_track_speed: false
set_cartesian_velo_continuous: false
set_allow_approx_motion: false
set_only_check_type: false
config_tgpio_reset_when_stop: false
config_cgpio_reset_when_stop: false
motion_enable: true
set_servo_attach: false
set_servo_detach: false
Expand All @@ -56,6 +84,7 @@ ufactory_driver:
get_position: false
get_servo_angle: true
get_position_aa: false
get_ft_sensor_data: false
set_pause_time: false
set_tcp_jerk: false
set_tcp_maxacc: false
Expand Down Expand Up @@ -104,4 +133,13 @@ ufactory_driver:
getset_tgpio_modbus_data: false
save_record_trajectory: false
load_trajectory: false
playback_trajectory: false
playback_trajectory: false
iden_tcp_load: false
ft_sensor_iden_load: false
ft_sensor_cali_load: false
config_force_control: false
set_impedance: false
set_impedance_mbk: false
set_impedance_config: false
set_linear_track_back_origin: false
set_linear_track_pos: false
92 changes: 92 additions & 0 deletions xarm_api/include/xarm_api/xarm_driver.h
Original file line number Diff line number Diff line change
Expand Up @@ -110,6 +110,12 @@ namespace xarm_api
rclcpp::Service<xarm_msgs::srv::Call>::SharedPtr service_clean_bio_gripper_error_;
rclcpp::Service<xarm_msgs::srv::Call>::SharedPtr service_start_record_trajectory_;
rclcpp::Service<xarm_msgs::srv::Call>::SharedPtr service_stop_record_trajectory_;
rclcpp::Service<xarm_msgs::srv::Call>::SharedPtr service_ft_sensor_set_zero_;
rclcpp::Service<xarm_msgs::srv::Call>::SharedPtr service_set_linear_track_stop_;
rclcpp::Service<xarm_msgs::srv::Call>::SharedPtr service_clean_linear_track_error_;
rclcpp::Service<xarm_msgs::srv::Call>::SharedPtr service_open_lite6_gripper_;
rclcpp::Service<xarm_msgs::srv::Call>::SharedPtr service_close_lite6_gripper_;
rclcpp::Service<xarm_msgs::srv::Call>::SharedPtr service_stop_lite6_gripper_;
bool _clean_error(const std::shared_ptr<xarm_msgs::srv::Call::Request> req, std::shared_ptr<xarm_msgs::srv::Call::Response> res);
bool _clean_warn(const std::shared_ptr<xarm_msgs::srv::Call::Request> req, std::shared_ptr<xarm_msgs::srv::Call::Response> res);
bool _clean_conf(const std::shared_ptr<xarm_msgs::srv::Call::Request> req, std::shared_ptr<xarm_msgs::srv::Call::Response> res);
Expand All @@ -121,6 +127,12 @@ namespace xarm_api
bool _clean_bio_gripper_error(const std::shared_ptr<xarm_msgs::srv::Call::Request> req, std::shared_ptr<xarm_msgs::srv::Call::Response> res);
bool _start_record_trajectory(const std::shared_ptr<xarm_msgs::srv::Call::Request> req, std::shared_ptr<xarm_msgs::srv::Call::Response> res);
bool _stop_record_trajectory(const std::shared_ptr<xarm_msgs::srv::Call::Request> req, std::shared_ptr<xarm_msgs::srv::Call::Response> res);
bool _ft_sensor_set_zero(const std::shared_ptr<xarm_msgs::srv::Call::Request> req, std::shared_ptr<xarm_msgs::srv::Call::Response> res);
bool _set_linear_track_stop(const std::shared_ptr<xarm_msgs::srv::Call::Request> req, std::shared_ptr<xarm_msgs::srv::Call::Response> res);
bool _clean_linear_track_error(const std::shared_ptr<xarm_msgs::srv::Call::Request> req, std::shared_ptr<xarm_msgs::srv::Call::Response> res);
bool _open_lite6_gripper(const std::shared_ptr<xarm_msgs::srv::Call::Request> req, std::shared_ptr<xarm_msgs::srv::Call::Response> res);
bool _close_lite6_gripper(const std::shared_ptr<xarm_msgs::srv::Call::Request> req, std::shared_ptr<xarm_msgs::srv::Call::Response> res);
bool _stop_lite6_gripper(const std::shared_ptr<xarm_msgs::srv::Call::Request> req, std::shared_ptr<xarm_msgs::srv::Call::Response> res);

// GetInt16
rclcpp::Service<xarm_msgs::srv::GetInt16>::SharedPtr service_get_state_;
Expand All @@ -129,16 +141,40 @@ namespace xarm_api
rclcpp::Service<xarm_msgs::srv::GetInt16>::SharedPtr service_get_gripper_err_code_;
rclcpp::Service<xarm_msgs::srv::GetInt16>::SharedPtr service_get_bio_gripper_status_;
rclcpp::Service<xarm_msgs::srv::GetInt16>::SharedPtr service_get_bio_gripper_error_;
rclcpp::Service<xarm_msgs::srv::GetInt16>::SharedPtr service_get_reduced_mode_;
rclcpp::Service<xarm_msgs::srv::GetInt16>::SharedPtr service_get_report_tau_or_i_;
rclcpp::Service<xarm_msgs::srv::GetInt16>::SharedPtr service_ft_sensor_app_get_;
rclcpp::Service<xarm_msgs::srv::GetInt16>::SharedPtr service_get_ft_sensor_error_;
rclcpp::Service<xarm_msgs::srv::GetInt16>::SharedPtr service_get_trajectory_rw_status_;
rclcpp::Service<xarm_msgs::srv::GetInt16>::SharedPtr service_get_linear_track_pos_;
rclcpp::Service<xarm_msgs::srv::GetInt16>::SharedPtr service_get_linear_track_status_;
rclcpp::Service<xarm_msgs::srv::GetInt16>::SharedPtr service_get_linear_track_error_;
rclcpp::Service<xarm_msgs::srv::GetInt16>::SharedPtr service_get_linear_track_is_enabled_;
rclcpp::Service<xarm_msgs::srv::GetInt16>::SharedPtr service_get_linear_track_on_zero_;
rclcpp::Service<xarm_msgs::srv::GetInt16>::SharedPtr service_get_linear_track_sci_;
bool _get_state(const std::shared_ptr<xarm_msgs::srv::GetInt16::Request> req, std::shared_ptr<xarm_msgs::srv::GetInt16::Response> res);
bool _get_cmdnum(const std::shared_ptr<xarm_msgs::srv::GetInt16::Request> req, std::shared_ptr<xarm_msgs::srv::GetInt16::Response> res);
bool _get_vacuum_gripper(const std::shared_ptr<xarm_msgs::srv::GetInt16::Request> req, std::shared_ptr<xarm_msgs::srv::GetInt16::Response> res);
bool _get_gripper_err_code(const std::shared_ptr<xarm_msgs::srv::GetInt16::Request> req, std::shared_ptr<xarm_msgs::srv::GetInt16::Response> res);
bool _get_bio_gripper_status(const std::shared_ptr<xarm_msgs::srv::GetInt16::Request> req, std::shared_ptr<xarm_msgs::srv::GetInt16::Response> res);
bool _get_bio_gripper_error(const std::shared_ptr<xarm_msgs::srv::GetInt16::Request> req, std::shared_ptr<xarm_msgs::srv::GetInt16::Response> res);
bool _get_reduced_mode(const std::shared_ptr<xarm_msgs::srv::GetInt16::Request> req, std::shared_ptr<xarm_msgs::srv::GetInt16::Response> res);
bool _get_report_tau_or_i(const std::shared_ptr<xarm_msgs::srv::GetInt16::Request> req, std::shared_ptr<xarm_msgs::srv::GetInt16::Response> res);
bool _ft_sensor_app_get(const std::shared_ptr<xarm_msgs::srv::GetInt16::Request> req, std::shared_ptr<xarm_msgs::srv::GetInt16::Response> res);
bool _get_ft_sensor_error(const std::shared_ptr<xarm_msgs::srv::GetInt16::Request> req, std::shared_ptr<xarm_msgs::srv::GetInt16::Response> res);
bool _get_trajectory_rw_status(const std::shared_ptr<xarm_msgs::srv::GetInt16::Request> req, std::shared_ptr<xarm_msgs::srv::GetInt16::Response> res);
bool _get_linear_track_pos(const std::shared_ptr<xarm_msgs::srv::GetInt16::Request> req, std::shared_ptr<xarm_msgs::srv::GetInt16::Response> res);
bool _get_linear_track_status(const std::shared_ptr<xarm_msgs::srv::GetInt16::Request> req, std::shared_ptr<xarm_msgs::srv::GetInt16::Response> res);
bool _get_linear_track_error(const std::shared_ptr<xarm_msgs::srv::GetInt16::Request> req, std::shared_ptr<xarm_msgs::srv::GetInt16::Response> res);
bool _get_linear_track_is_enabled(const std::shared_ptr<xarm_msgs::srv::GetInt16::Request> req, std::shared_ptr<xarm_msgs::srv::GetInt16::Response> res);
bool _get_linear_track_on_zero(const std::shared_ptr<xarm_msgs::srv::GetInt16::Request> req, std::shared_ptr<xarm_msgs::srv::GetInt16::Response> res);
bool _get_linear_track_sci(const std::shared_ptr<xarm_msgs::srv::GetInt16::Request> req, std::shared_ptr<xarm_msgs::srv::GetInt16::Response> res);

// GetInt16List
rclcpp::Service<xarm_msgs::srv::GetInt16List>::SharedPtr service_get_err_warn_code_;
rclcpp::Service<xarm_msgs::srv::GetInt16List>::SharedPtr service_get_linear_track_sco_;
bool _get_err_warn_code(const std::shared_ptr<xarm_msgs::srv::GetInt16List::Request> req, std::shared_ptr<xarm_msgs::srv::GetInt16List::Response> res);
bool _get_linear_track_sco(const std::shared_ptr<xarm_msgs::srv::GetInt16List::Request> req, std::shared_ptr<xarm_msgs::srv::GetInt16List::Response> res);

// SetInt16
rclcpp::Service<xarm_msgs::srv::SetInt16>::SharedPtr service_set_mode_;
Expand All @@ -154,6 +190,16 @@ namespace xarm_api
rclcpp::Service<xarm_msgs::srv::SetInt16>::SharedPtr service_set_self_collision_detection_;
rclcpp::Service<xarm_msgs::srv::SetInt16>::SharedPtr service_set_simulation_robot_;
rclcpp::Service<xarm_msgs::srv::SetInt16>::SharedPtr service_set_baud_checkset_enable_;
rclcpp::Service<xarm_msgs::srv::SetInt16>::SharedPtr service_set_report_tau_or_i_;
rclcpp::Service<xarm_msgs::srv::SetInt16>::SharedPtr service_ft_sensor_enable_;
rclcpp::Service<xarm_msgs::srv::SetInt16>::SharedPtr service_ft_sensor_app_set_;
rclcpp::Service<xarm_msgs::srv::SetInt16>::SharedPtr service_set_linear_track_enable_;
rclcpp::Service<xarm_msgs::srv::SetInt16>::SharedPtr service_set_linear_track_speed_;
rclcpp::Service<xarm_msgs::srv::SetInt16>::SharedPtr service_set_cartesian_velo_continuous_;
rclcpp::Service<xarm_msgs::srv::SetInt16>::SharedPtr service_set_allow_approx_motion_;
rclcpp::Service<xarm_msgs::srv::SetInt16>::SharedPtr service_set_only_check_type_;
rclcpp::Service<xarm_msgs::srv::SetInt16>::SharedPtr service_config_tgpio_reset_when_stop_;
rclcpp::Service<xarm_msgs::srv::SetInt16>::SharedPtr service_config_cgpio_reset_when_stop_;
bool _set_mode(const std::shared_ptr<xarm_msgs::srv::SetInt16::Request> req, std::shared_ptr<xarm_msgs::srv::SetInt16::Response> res);
bool _set_state(const std::shared_ptr<xarm_msgs::srv::SetInt16::Request> req, std::shared_ptr<xarm_msgs::srv::SetInt16::Response> res);
bool _set_collision_sensitivity(const std::shared_ptr<xarm_msgs::srv::SetInt16::Request> req, std::shared_ptr<xarm_msgs::srv::SetInt16::Response> res);
Expand All @@ -167,6 +213,16 @@ namespace xarm_api
bool _set_self_collision_detection(const std::shared_ptr<xarm_msgs::srv::SetInt16::Request> req, std::shared_ptr<xarm_msgs::srv::SetInt16::Response> res);
bool _set_simulation_robot(const std::shared_ptr<xarm_msgs::srv::SetInt16::Request> req, std::shared_ptr<xarm_msgs::srv::SetInt16::Response> res);
bool _set_baud_checkset_enable(const std::shared_ptr<xarm_msgs::srv::SetInt16::Request> req, std::shared_ptr<xarm_msgs::srv::SetInt16::Response> res);
bool _set_report_tau_or_i(const std::shared_ptr<xarm_msgs::srv::SetInt16::Request> req, std::shared_ptr<xarm_msgs::srv::SetInt16::Response> res);
bool _ft_sensor_enable(const std::shared_ptr<xarm_msgs::srv::SetInt16::Request> req, std::shared_ptr<xarm_msgs::srv::SetInt16::Response> res);
bool _ft_sensor_app_set(const std::shared_ptr<xarm_msgs::srv::SetInt16::Request> req, std::shared_ptr<xarm_msgs::srv::SetInt16::Response> res);
bool _set_linear_track_enable(const std::shared_ptr<xarm_msgs::srv::SetInt16::Request> req, std::shared_ptr<xarm_msgs::srv::SetInt16::Response> res);
bool _set_linear_track_speed(const std::shared_ptr<xarm_msgs::srv::SetInt16::Request> req, std::shared_ptr<xarm_msgs::srv::SetInt16::Response> res);
bool _set_cartesian_velo_continuous(const std::shared_ptr<xarm_msgs::srv::SetInt16::Request> req, std::shared_ptr<xarm_msgs::srv::SetInt16::Response> res);
bool _set_allow_approx_motion(const std::shared_ptr<xarm_msgs::srv::SetInt16::Request> req, std::shared_ptr<xarm_msgs::srv::SetInt16::Response> res);
bool _set_only_check_type(const std::shared_ptr<xarm_msgs::srv::SetInt16::Request> req, std::shared_ptr<xarm_msgs::srv::SetInt16::Response> res);
bool _config_tgpio_reset_when_stop(const std::shared_ptr<xarm_msgs::srv::SetInt16::Request> req, std::shared_ptr<xarm_msgs::srv::SetInt16::Response> res);
bool _config_cgpio_reset_when_stop(const std::shared_ptr<xarm_msgs::srv::SetInt16::Request> req, std::shared_ptr<xarm_msgs::srv::SetInt16::Response> res);

// SetInt16ById
rclcpp::Service<xarm_msgs::srv::SetInt16ById>::SharedPtr service_motion_enable_;
Expand Down Expand Up @@ -204,9 +260,11 @@ namespace xarm_api
rclcpp::Service<xarm_msgs::srv::GetFloat32List>::SharedPtr service_get_position_;
rclcpp::Service<xarm_msgs::srv::GetFloat32List>::SharedPtr service_get_servo_angle_;
rclcpp::Service<xarm_msgs::srv::GetFloat32List>::SharedPtr service_get_position_aa_;
rclcpp::Service<xarm_msgs::srv::GetFloat32List>::SharedPtr service_get_ft_sensor_data_;
bool _get_position(const std::shared_ptr<xarm_msgs::srv::GetFloat32List::Request> req, std::shared_ptr<xarm_msgs::srv::GetFloat32List::Response> res);
bool _get_servo_angle(const std::shared_ptr<xarm_msgs::srv::GetFloat32List::Request> req, std::shared_ptr<xarm_msgs::srv::GetFloat32List::Response> res);
bool _get_position_aa(const std::shared_ptr<xarm_msgs::srv::GetFloat32List::Request> req, std::shared_ptr<xarm_msgs::srv::GetFloat32List::Response> res);
bool _get_ft_sensor_data(const std::shared_ptr<xarm_msgs::srv::GetFloat32List::Request> req, std::shared_ptr<xarm_msgs::srv::GetFloat32List::Response> res);

// SetFloat32
rclcpp::Service<xarm_msgs::srv::SetFloat32>::SharedPtr service_set_pause_time_;
Expand Down Expand Up @@ -355,6 +413,40 @@ namespace xarm_api
// TrajPlay
rclcpp::Service<xarm_msgs::srv::TrajPlay>::SharedPtr service_playback_trajectory_;
bool _playback_trajectory(const std::shared_ptr<xarm_msgs::srv::TrajPlay::Request> req, std::shared_ptr<xarm_msgs::srv::TrajPlay::Response> res);

// IdenLoad
rclcpp::Service<xarm_msgs::srv::IdenLoad>::SharedPtr service_iden_tcp_load_;
rclcpp::Service<xarm_msgs::srv::IdenLoad>::SharedPtr service_ft_sensor_iden_load_;
bool _iden_tcp_load(const std::shared_ptr<xarm_msgs::srv::IdenLoad::Request> req, std::shared_ptr<xarm_msgs::srv::IdenLoad::Response> res);
bool _ft_sensor_iden_load(const std::shared_ptr<xarm_msgs::srv::IdenLoad::Request> req, std::shared_ptr<xarm_msgs::srv::IdenLoad::Response> res);

// FtCaliLoad
rclcpp::Service<xarm_msgs::srv::FtCaliLoad>::SharedPtr service_ft_sensor_cali_load_;
bool _ft_sensor_cali_load(const std::shared_ptr<xarm_msgs::srv::FtCaliLoad::Request> req, std::shared_ptr<xarm_msgs::srv::FtCaliLoad::Response> res);

// FtForceConfig
rclcpp::Service<xarm_msgs::srv::FtForceConfig>::SharedPtr service_config_force_control_;
bool _config_force_control(const std::shared_ptr<xarm_msgs::srv::FtForceConfig::Request> req, std::shared_ptr<xarm_msgs::srv::FtForceConfig::Response> res);

// FtForcePid
rclcpp::Service<xarm_msgs::srv::FtForcePid>::SharedPtr service_set_force_control_pid_;
bool _set_force_control_pid(const std::shared_ptr<xarm_msgs::srv::FtForcePid::Request> req, std::shared_ptr<xarm_msgs::srv::FtForcePid::Response> res);

// FtImpedance
rclcpp::Service<xarm_msgs::srv::FtImpedance>::SharedPtr service_set_impedance_;
rclcpp::Service<xarm_msgs::srv::FtImpedance>::SharedPtr service_set_impedance_mbk_;
rclcpp::Service<xarm_msgs::srv::FtImpedance>::SharedPtr service_set_impedance_config_;
bool _set_impedance(const std::shared_ptr<xarm_msgs::srv::FtImpedance::Request> req, std::shared_ptr<xarm_msgs::srv::FtImpedance::Response> res);
bool _set_impedance_mbk(const std::shared_ptr<xarm_msgs::srv::FtImpedance::Request> req, std::shared_ptr<xarm_msgs::srv::FtImpedance::Response> res);
bool _set_impedance_config(const std::shared_ptr<xarm_msgs::srv::FtImpedance::Request> req, std::shared_ptr<xarm_msgs::srv::FtImpedance::Response> res);

// LinearTrackBackOrigin
rclcpp::Service<xarm_msgs::srv::LinearTrackBackOrigin>::SharedPtr service_set_linear_track_back_origin_;
bool _set_linear_track_back_origin(const std::shared_ptr<xarm_msgs::srv::LinearTrackBackOrigin::Request> req, std::shared_ptr<xarm_msgs::srv::LinearTrackBackOrigin::Response> res);

// LinearTrackSetPos
rclcpp::Service<xarm_msgs::srv::LinearTrackSetPos>::SharedPtr service_set_linear_track_pos_;
bool _set_linear_track_pos(const std::shared_ptr<xarm_msgs::srv::LinearTrackSetPos::Request> req, std::shared_ptr<xarm_msgs::srv::LinearTrackSetPos::Response> res);
};
}

Expand Down
7 changes: 7 additions & 0 deletions xarm_api/include/xarm_api/xarm_msgs.h
Original file line number Diff line number Diff line change
Expand Up @@ -41,5 +41,12 @@
#include <xarm_msgs/srv/traj_play.hpp>
#include <xarm_msgs/srv/vacuum_gripper_ctrl.hpp>
#include <xarm_msgs/srv/set_modbus_timeout.hpp>
#include <xarm_msgs/srv/iden_load.hpp>
#include <xarm_msgs/srv/ft_cali_load.hpp>
#include <xarm_msgs/srv/ft_force_config.hpp>
#include <xarm_msgs/srv/ft_force_pid.hpp>
#include <xarm_msgs/srv/ft_impedance.hpp>
#include <xarm_msgs/srv/linear_track_back_origin.hpp>
#include <xarm_msgs/srv/linear_track_set_pos.hpp>

#endif // __XARM_MSGS_H
Loading

0 comments on commit a08120a

Please sign in to comment.