Class CartesianMotionBase
Defined in File cartesian_motion_base.hpp
Inheritance Relationships
Base Type
public rclcpp::Node
Class Documentation
-
class CartesianMotionBase : public rclcpp::Node
Base class for robot motion tasks.
- Param node_name:
Name of the node.
- Param robot_configs:
Vector of robot configurations.
- Param rate:
Rate of the task execution.
Public Functions
-
inline explicit CartesianMotionBase(const std::string &node_name, std::vector<RobotConfig> robot_configs = {RobotConfig()}, uint16_t rate = 125)
-
virtual ~CartesianMotionBase() = default
-
void start()
-
inline void active()
-
inline void deactivate()
Protected Functions
-
inline virtual void on_init()
A interface for user to implement their own initialization function. Usually used for ROS related initialization.
-
virtual void tasks_init() = 0
A interface for user to implement their own task initialization function. Usually used for initializing the FSM tasks.
- Attention
This function must be implemented by the user.
-
inline virtual geometry_msgs::msg::PoseStamped intepolation(geometry_msgs::msg::PoseStamped init_pose, geometry_msgs::msg::PoseStamped target_pose, double duration, double current_duration)
Interpolation between two poses. Default is linear interpolation for position and slerp for orientation.
- Parameters:
init_pose – Initial pose.
target_pose – Target pose.
duration – Duration of the interpolation.
current_duration – Current time in the interpolation.
- Returns:
Interpolated pose.
-
inline virtual geometry_msgs::msg::WrenchStamped intepolation_wrench(geometry_msgs::msg::WrenchStamped init_wrench, geometry_msgs::msg::WrenchStamped target_wrench, double duration, double current_duration)
Interpolation between two wrenches. Default is linear interpolation.
- Parameters:
init_wrench – Initial wrench.
target_wrench – Target wrench.
duration – Duration of the interpolation.
current_duration – Current time in the interpolation.
- Returns:
Interpolated wrench.
-
inline std::vector<std::string> get_robot_names()
get robot names
- Returns:
vector of robot names
-
inline const geometry_msgs::msg::PoseStamped get_current_pose(std::string name)
get current pose for a robot by name
- Parameters:
robot_name –
- Returns:
current pose
-
inline const geometry_msgs::msg::WrenchStamped get_current_wrench(std::string name)
get current wrench for a robot by name
- Parameters:
robot_name –
- Returns:
current wrench
-
inline const geometry_msgs::msg::PoseStamped get_start_pose(std::string name)
get start pose for a robot by name
- Parameters:
robot_name –
- Returns:
start pose
-
inline const geometry_msgs::msg::WrenchStamped get_start_wrench(std::string name)
get start wrench for a robot by name
- Parameters:
robot_name –
- Returns:
start wrench
-
inline const geometry_msgs::msg::PoseStamped get_target_monitor(std::string name)
get current target monitor pose for a robot by name
- Parameters:
robot_name –
- Returns:
target monitor pose
-
inline SystemState get_system_state()
get system state
- Returns:
system state. The system state includes current task number, start time, and current time.
-
inline void set_target_pose(PoseMap target_pose)
set target pose for a robot by name
- Parameters:
robot_name –
target_pose –
-
inline void set_target_wrench(WrenchMap target_wrench)
set target wrench for a robot by name
- Parameters:
robot_name –
target_wrench –
-
bool move(PoseMap target_poses, double duration)
from start_pose(initialized when this task running) to target_pose
- Parameters:
target_poses – map of robot name and target poses
duration –
- Returns:
finish or not
-
bool move_wrench(PoseMap target_poses, WrenchMap target_wrenches, double duration)
from start_pose(initialized when this task running) to target_pose
- Parameters:
target_poses – map of robot name and target poses
target_wrenches – map of robot name and target wrenches
duration –
- Returns:
finish or not
-
bool sleep(double duration)
sleep for a while
- Parameters:
duration –
- Returns:
finish or not
-
bool joint_move(JointMap target_joints, double time)
joint move
- Parameters:
target_joints – map of robot name and target joint positions
time –
- Returns:
finish or not
Push back the task, the task is derived from GarmentTaskBase.
- Parameters:
task –
- Returns:
the task number
-
void task_execute()
-
inline void set_task_finished()
Set the task finished, go to the next task.
-
inline void goto_specific_task(size_t task_num)
Go to a specific task number. You can get the task number when you push back the task.
- Parameters:
task_num –
-
inline void goto_init_task()
Go to the initial task.
-
inline void goto_last_task()
Go to the last task.
-
inline bool check_init()
Protected Attributes
-
SystemState system_state_
-
uint8_t next_task_offset_ = 1
-
std::thread control_loop_thread_
-
rclcpp::Clock my_clock_
-
std::vector<std::shared_ptr<cartesian_motion_base::MotionTask>> tasks_vector_
-
bool active_ = true