Airbot SDK 5.1.6
This project is designed for airbot C++SDK
Loading...
Searching...
No Matches
airbot_sdk.hpp
Go to the documentation of this file.
1#ifndef AIRBOT_SDK_HPP_
2#define AIRBOT_SDK_HPP_
3
16#include <spdlog/sinks/stdout_color_sinks.h>
17#include <spdlog/spdlog.h>
18
19#include <array>
20#include <future>
21#include <memory>
22#include <string>
23#include <variant>
24#include <vector>
25
26#include "driver_state.hpp"
27#include "robot_mode.hpp"
28#include "speed_profile.hpp"
29
30namespace airbot {
31
32// Forward declaration of AirbotArm class
33class AirbotArm;
34
57class AirbotSdk {
58 public:
67 AirbotSdk(const std::string& url = "localhost", const unsigned int port = 50051);
68
75 const std::shared_ptr<spdlog::logger> GetLogger() const;
76
83 bool IsRunning() const;
84
91 bool Connect() const;
92
99 bool Disconnect();
100
107 std::vector<std::pair<std::string, std::vector<std::string>>> GetProductInfo() const;
108
116
124
125 // /**
126 // * @brief Retrieves the modes available for each robot component.
127 // * @return A pair containing two vectors: one with component names and one with their corresponding modes.
128 // *
129 // * Retrieves the available control modes for each component of the robotic arm.
130 // */
131 // std::pair<std::vector<std::string>, std::vector<RobotMode>> GetMode() const;
132
140 std::vector<std::pair<std::string, std::variant<int32_t, double, std::string, bool>>> GetParams(
141 std::vector<std::string> names) const;
142
149 std::pair<std::array<double, 3>, std::array<double, 4>> GetEndPose() const;
150
157 std::array<double, 6> GetJointPos() const;
158
165 std::array<double, 6> GetJointVel() const;
166
173 std::array<double, 6> GetJointEff() const;
174
181 std::vector<double> GetEefPos() const;
182
189 std::vector<double> GetEefVel() const;
190
197 std::vector<double> GetEefEff() const;
198
209 const std::vector<std::pair<std::string, std::variant<int32_t, double, std::string, bool>>>& params) const;
210
225 bool SetSpeedProfile(const SpeedProfile& profile) const;
226
247 bool SwitchMode(const RobotMode& mode) const;
248
259 bool SwitchMode(const std::vector<std::string>& component_names, const std::vector<RobotMode>& modes) const;
260
271 bool LoadApp(const std::string& name = "record_replay_app/record_replay_app::RecordReplayApp",
272 const std::vector<std::pair<std::string, std::string>>& params = {}) const;
273
281 bool UnloadApp() const;
282
292 bool MoveToJointPos(const std::array<double, 6>& joint_pos) const;
293
303 std::future<bool> AsyncMoveToJointPos(const std::array<double, 6>& joint_pos) const;
304
314 bool MoveToCartPos(const std::pair<std::array<double, 3>, std::array<double, 4>>& cart_pos) const;
315
325 std::future<bool> AsyncMoveToCartPos(const std::pair<std::array<double, 3>, std::array<double, 4>>& cart_pos) const;
326
345 bool MoveEefPos(const std::vector<double>& eef_pos) const;
346
356 std::future<bool> AsyncMoveEefPos(const std::vector<double>& eef_pos) const;
357
367 bool MoveEefPos(const double& eef_pos) const;
368
378 std::future<bool> AsyncMoveEefPos(const double& eef_pos) const;
379
391 const std::vector<std::pair<std::array<double, 3>, std::array<double, 4>>>& cart_waypoints) const;
392
404 std::future<bool> AsyncMoveWithCartWaypoints(
405 const std::vector<std::pair<std::array<double, 3>, std::array<double, 4>>>& cart_waypoints) const;
406
415 bool MoveWithJointWaypoints(const std::vector<std::array<double, 6>>& joint_waypoints) const;
416
426 std::future<bool> AsyncMoveWithJointWaypoints(const std::vector<std::array<double, 6>>& joint_waypoints) const;
427
443 void MitJointIntegratedControl(const std::array<double, 6>& joint_pos, const std::array<double, 6>& joint_vel,
444 const std::array<double, 6>& joint_eff, const std::array<double, 6>& joint_kp,
445 const std::array<double, 6>& joint_kd) const;
446
454 void ServoJointPos(const std::array<double, 6>& joint_pos) const;
455
463 void ServoJointVel(const std::array<double, 6>& joint_vel) const;
464
472 void ServoCartPos(const std::pair<std::array<double, 3>, std::array<double, 4>>& cart_pos) const;
473
482 void ServoCartTwist(const std::pair<std::array<double, 3>, std::array<double, 3>>& twist) const;
483
491 void ServoEefPos(const std::vector<double>& eef_pos) const;
492
500 void ServoEefPos(const double& eef_pos) const;
501
509
510 private:
511 std::shared_ptr<spdlog::logger> logger_;
512 std::unique_ptr<AirbotArm>
513 arm_;
514};
515
516} // namespace airbot
517
518#endif // AIRBOT_SDK_HPP_
Core class for interacting with the Airbot robotic arm.
Definition airbot_sdk.hpp:57
std::vector< double > GetEefPos() const
Retrieves the current position of the end-effector (EEF).
bool MoveToCartPos(const std::pair< std::array< double, 3 >, std::array< double, 4 > > &cart_pos) const
Moves the robotic arm to the specified Cartesian position and orientation.
bool MoveEefPos(const std::vector< double > &eef_pos) const
Moves the robotic arm's end-effector to the specified position.
std::vector< std::pair< std::string, std::vector< std::string > > > GetProductInfo() const
Retrieves product information (e.g., name, version) from the robotic arm.
const std::shared_ptr< spdlog::logger > GetLogger() const
Retrieves the logger used by the SDK.
bool SwitchMode(const std::vector< std::string > &component_names, const std::vector< RobotMode > &modes) const
Switches the control mode for multiple robot components.
std::future< bool > AsyncMoveToJointPos(const std::array< double, 6 > &joint_pos) const
Asynchronously moves the robotic arm to the specified joint positions.
void ServoJointPos(const std::array< double, 6 > &joint_pos) const
Directly controls the robotic arm's joints to move to the specified positions.
void ServoEefPos(const std::vector< double > &eef_pos) const
Directly controls the robotic arm's end-effector position.
bool MoveWithCartWaypoints(const std::vector< std::pair< std::array< double, 3 >, std::array< double, 4 > > > &cart_waypoints) const
Moves the robotic arm along specified Cartesian waypoints.
void ServoJointVel(const std::array< double, 6 > &joint_vel) const
Directly controls the robotic arm's joints to move at the specified velocities.
std::future< bool > AsyncMoveWithCartWaypoints(const std::vector< std::pair< std::array< double, 3 >, std::array< double, 4 > > > &cart_waypoints) const
Asynchronously moves the robotic arm along specified Cartesian waypoints.
std::vector< double > GetEefVel() const
Retrieves the current velocity of the end-effector (EEF).
std::future< bool > AsyncMoveEefPos(const double &eef_pos) const
Asynchronously moves the robotic arm's end-effector to the specified position (single value).
std::vector< double > GetEefEff() const
Retrieves the current force/effort of the end-effector (EEF).
AirbotSdk(const std::string &url="localhost", const unsigned int port=50051)
Constructor that initializes the SDK with the given connection details.
bool MoveWithJointWaypoints(const std::vector< std::array< double, 6 > > &joint_waypoints) const
Moves the robotic arm along specified joint waypoints.
bool Disconnect()
Disconnects from the robotic arm.
std::future< bool > AsyncMoveWithJointWaypoints(const std::vector< std::array< double, 6 > > &joint_waypoints) const
Asynchronously moves the robotic arm along specified joint waypoints.
bool MoveEefPos(const double &eef_pos) const
Moves the robotic arm's end-effector to the specified position (single value).
bool Connect() const
Establishes a connection to the robotic arm.
bool SwitchMode(const RobotMode &mode) const
Switches the control mode of the robotic arm.
void ServoCartPos(const std::pair< std::array< double, 3 >, std::array< double, 4 > > &cart_pos) const
Directly controls the robotic arm's end-effector position.
std::array< double, 6 > GetJointEff() const
Retrieves the current joint efforts (torques) of the robotic arm.
std::vector< std::pair< std::string, std::variant< int32_t, double, std::string, bool > > > GetParams(std::vector< std::string > names) const
Retrieves the modes available for each robot component.
std::array< double, 6 > GetJointVel() const
Retrieves the current joint velocities of the robotic arm.
std::future< bool > AsyncMoveToCartPos(const std::pair< std::array< double, 3 >, std::array< double, 4 > > &cart_pos) const
Asynchronously moves the robotic arm to the specified Cartesian position and orientation.
void ServoCartTwist(const std::pair< std::array< double, 3 >, std::array< double, 3 > > &twist) const
Directly controls the robotic arm's twist (linear and angular velocity) in Cartesian space.
bool IsRunning() const
Checks if the SDK is running and connected to the robotic arm.
bool LoadApp(const std::string &name="record_replay_app/record_replay_app::RecordReplayApp", const std::vector< std::pair< std::string, std::string > > &params={}) const
Loads an application onto the robotic arm.
State GetState() const
Retrieves the current state of the robotic arm.
void MitJointIntegratedControl(const std::array< double, 6 > &joint_pos, const std::array< double, 6 > &joint_vel, const std::array< double, 6 > &joint_eff, const std::array< double, 6 > &joint_kp, const std::array< double, 6 > &joint_kd) const
Sends integrated MIT control commands to the robotic arm's joints.
bool SetParams(const std::vector< std::pair< std::string, std::variant< int32_t, double, std::string, bool > > > &params) const
Sets the parameters of the robotic arm.
bool MoveToJointPos(const std::array< double, 6 > &joint_pos) const
Moves the robotic arm to the specified joint positions.
std::future< bool > AsyncMoveEefPos(const std::vector< double > &eef_pos) const
Asynchronously moves the robotic arm's end-effector to the specified position.
std::array< double, 6 > GetJointPos() const
Retrieves the current joint positions of the robotic arm.
bool UnloadApp() const
Unloads the currently loaded application from the robotic arm.
void ServoEefPos(const double &eef_pos) const
Directly controls the robotic arm's end-effector position (single value).
bool SetSpeedProfile(const SpeedProfile &profile) const
Sets the speed profile for the robotic arm.
RobotMode GetControlMode() const
Retrieves the current control mode of the robotic arm.
~AirbotSdk()
Destructor that cleans up resources used by the SDK.
std::pair< std::array< double, 3 >, std::array< double, 4 > > GetEndPose() const
Retrieves the end-effector pose (position and orientation) of the robotic arm.
Defines operational states for the driver service.
Namespace containing all Airbot SDK related definitions.
RobotMode
Enum class representing the control modes of the robot arm.
Definition robot_mode.hpp:30
State
Enum representing the operational states of the driver service.
Definition driver_state.hpp:27
SpeedProfile
Enum representing predefined speed profiles for robot operation.
Definition speed_profile.hpp:26
Defines control modes for robot arm operations.
Defines speed profiles for robot motion control.