16#include <spdlog/sinks/stdout_color_sinks.h>
17#include <spdlog/spdlog.h>
67 AirbotSdk(
const std::string& url =
"localhost",
const unsigned int port = 50051);
75 const std::shared_ptr<spdlog::logger>
GetLogger()
const;
107 std::vector<std::pair<std::string, std::vector<std::string>>>
GetProductInfo()
const;
140 std::vector<std::pair<std::string, std::variant<int32_t, double, std::string, bool>>>
GetParams(
141 std::vector<std::string> names)
const;
149 std::pair<std::array<double, 3>, std::array<double, 4>>
GetEndPose()
const;
209 const std::vector<std::pair<std::string, std::variant<int32_t, double, std::string, bool>>>& params)
const;
259 bool SwitchMode(
const std::vector<std::string>& component_names,
const std::vector<RobotMode>& modes)
const;
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;
314 bool MoveToCartPos(
const std::pair<std::array<double, 3>, std::array<double, 4>>& cart_pos)
const;
325 std::future<bool>
AsyncMoveToCartPos(
const std::pair<std::array<double, 3>, std::array<double, 4>>& cart_pos)
const;
391 const std::vector<std::pair<std::array<double, 3>, std::array<double, 4>>>& cart_waypoints)
const;
405 const std::vector<std::pair<std::array<double, 3>, std::array<double, 4>>>& cart_waypoints)
const;
444 const std::array<double, 6>& joint_eff,
const std::array<double, 6>& joint_kp,
445 const std::array<double, 6>& joint_kd)
const;
472 void ServoCartPos(
const std::pair<std::array<double, 3>, std::array<double, 4>>& cart_pos)
const;
482 void ServoCartTwist(
const std::pair<std::array<double, 3>, std::array<double, 3>>& twist)
const;
511 std::shared_ptr<spdlog::logger> logger_;
512 std::unique_ptr<AirbotArm>
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 > > ¶ms={}) 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 > > > ¶ms) 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.