#include <single_arm_controller.hpp>
◆ SingleArmController()
wbc_ros::SingleArmController::SingleArmController |
( |
const rclcpp::NodeOptions & | options = rclcpp::NodeOptions() | ) |
|
◆ ~SingleArmController()
wbc_ros::SingleArmController::~SingleArmController |
( |
| ) |
|
|
inline |
◆ ee_pose_callback()
void wbc_ros::SingleArmController::ee_pose_callback |
( |
const RigidBodyStateMsgPtr | msg | ) |
|
◆ elbow_pose_callback()
void wbc_ros::SingleArmController::elbow_pose_callback |
( |
const RigidBodyStateMsgPtr | msg | ) |
|
◆ joint_position_callback()
void wbc_ros::SingleArmController::joint_position_callback |
( |
const JointCommandMsgPtr | msg | ) |
|
◆ joint_weight_callback()
void wbc_ros::SingleArmController::joint_weight_callback |
( |
const JointWeightMsgPtr | msg | ) |
|
◆ on_activate()
rclcpp_lifecycle::LifecycleNode::CallbackReturn wbc_ros::SingleArmController::on_activate |
( |
const rclcpp_lifecycle::State & | previous_state | ) |
|
|
overridevirtual |
◆ on_cleanup()
rclcpp_lifecycle::LifecycleNode::CallbackReturn wbc_ros::SingleArmController::on_cleanup |
( |
const rclcpp_lifecycle::State & | previous_state | ) |
|
|
overridevirtual |
◆ on_configure()
rclcpp_lifecycle::LifecycleNode::CallbackReturn wbc_ros::SingleArmController::on_configure |
( |
const rclcpp_lifecycle::State & | previous_state | ) |
|
|
overridevirtual |
◆ on_deactivate()
rclcpp_lifecycle::LifecycleNode::CallbackReturn wbc_ros::SingleArmController::on_deactivate |
( |
const rclcpp_lifecycle::State & | previous_state | ) |
|
|
overridevirtual |
◆ on_error()
rclcpp_lifecycle::LifecycleNode::CallbackReturn wbc_ros::SingleArmController::on_error |
( |
const rclcpp_lifecycle::State & | previous_state | ) |
|
|
overridevirtual |
◆ on_shutdown()
rclcpp_lifecycle::LifecycleNode::CallbackReturn wbc_ros::SingleArmController::on_shutdown |
( |
const rclcpp_lifecycle::State & | previous_state | ) |
|
|
overridevirtual |
◆ robot_state_callback()
void wbc_ros::SingleArmController::robot_state_callback |
( |
const RobotStateMsgPtr | msg | ) |
|
◆ updateController()
void wbc_ros::SingleArmController::updateController |
( |
| ) |
|
◆ ee_pose
wbc::types::RigidBodyState wbc_ros::SingleArmController::ee_pose |
|
protected |
◆ ee_pose_controller
wbc::CartesianPosPDControllerPtr wbc_ros::SingleArmController::ee_pose_controller |
|
protected |
◆ ee_pose_msg
RigidBodyStateMsgPtr wbc_ros::SingleArmController::ee_pose_msg |
|
protected |
◆ ee_pose_subscriber
RigidBodyStateSubscription wbc_ros::SingleArmController::ee_pose_subscriber |
|
protected |
◆ ee_pose_task
wbc::SpatialVelocityTaskPtr wbc_ros::SingleArmController::ee_pose_task |
|
protected |
◆ elbow_pose
wbc::types::RigidBodyState wbc_ros::SingleArmController::elbow_pose |
|
protected |
◆ elbow_pose_controller
wbc::CartesianPosPDControllerPtr wbc_ros::SingleArmController::elbow_pose_controller |
|
protected |
◆ elbow_pose_msg
RigidBodyStateMsgPtr wbc_ros::SingleArmController::elbow_pose_msg |
|
protected |
◆ elbow_pose_subscriber
RigidBodyStateSubscription wbc_ros::SingleArmController::elbow_pose_subscriber |
|
protected |
◆ elbow_pose_task
wbc::SpatialVelocityTaskPtr wbc_ros::SingleArmController::elbow_pose_task |
|
protected |
◆ has_robot_state
bool wbc_ros::SingleArmController::has_robot_state |
|
protected |
◆ joint_idx_map
std::vector<int> wbc_ros::SingleArmController::joint_idx_map |
|
protected |
◆ joint_integrator
wbc::JointIntegrator wbc_ros::SingleArmController::joint_integrator |
|
protected |
◆ joint_pos_controller
wbc::JointPosPDControllerPtr wbc_ros::SingleArmController::joint_pos_controller |
|
protected |
◆ joint_position
wbc::types::JointCommand wbc_ros::SingleArmController::joint_position |
|
protected |
◆ joint_position_msg
JointCommandMsgPtr wbc_ros::SingleArmController::joint_position_msg |
|
protected |
◆ joint_position_subscriber
JointCommandSubscription wbc_ros::SingleArmController::joint_position_subscriber |
|
protected |
◆ joint_position_task
wbc::JointVelocityTaskPtr wbc_ros::SingleArmController::joint_position_task |
|
protected |
◆ joint_state
wbc::types::JointState wbc_ros::SingleArmController::joint_state |
|
protected |
◆ joint_weight_msg
JointWeightMsgPtr wbc_ros::SingleArmController::joint_weight_msg |
|
protected |
◆ joint_weight_subscriber
JointWeightSubscription wbc_ros::SingleArmController::joint_weight_subscriber |
|
protected |
◆ param_listener
std::shared_ptr<single_arm_controller::ParamListener> wbc_ros::SingleArmController::param_listener |
|
protected |
◆ params
single_arm_controller::Params wbc_ros::SingleArmController::params |
|
protected |
◆ qp
wbc::HierarchicalQP wbc_ros::SingleArmController::qp |
|
protected |
◆ robot_model
wbc::RobotModelPtr wbc_ros::SingleArmController::robot_model |
|
protected |
◆ robot_state_msg
RobotStateMsgPtr wbc_ros::SingleArmController::robot_state_msg |
|
protected |
◆ robot_state_subscriber
RobotStateSubscription wbc_ros::SingleArmController::robot_state_subscriber |
|
protected |
◆ rt_ee_pose_buffer
RTRigidBodyStateBuffer wbc_ros::SingleArmController::rt_ee_pose_buffer |
|
protected |
◆ rt_elbow_pose_buffer
RTRigidBodyStateBuffer wbc_ros::SingleArmController::rt_elbow_pose_buffer |
|
protected |
◆ rt_joint_position_buffer
RTJointCommandBuffer wbc_ros::SingleArmController::rt_joint_position_buffer |
|
protected |
◆ rt_joint_weight_buffer
RTJointWeightBuffer wbc_ros::SingleArmController::rt_joint_weight_buffer |
|
protected |
◆ rt_robot_state_buffer
RTRobotStateBuffer wbc_ros::SingleArmController::rt_robot_state_buffer |
|
protected |
◆ rt_solver_output_publisher
std::unique_ptr<RTCommandPublisher> wbc_ros::SingleArmController::rt_solver_output_publisher |
|
protected |
◆ rt_timing_stats_publisher
std::unique_ptr<RTTimingStatsPublisher> wbc_ros::SingleArmController::rt_timing_stats_publisher |
|
protected |
◆ scene
wbc::ScenePtr wbc_ros::SingleArmController::scene |
|
protected |
◆ solver
wbc::QPSolverPtr wbc_ros::SingleArmController::solver |
|
protected |
◆ solver_output
wbc::types::JointCommand wbc_ros::SingleArmController::solver_output |
|
protected |
◆ solver_output_msg
CommandMsg wbc_ros::SingleArmController::solver_output_msg |
|
protected |
◆ solver_output_publisher
CommandPublisher::SharedPtr wbc_ros::SingleArmController::solver_output_publisher |
|
protected |
◆ stamp
rclcpp::Time wbc_ros::SingleArmController::stamp |
|
protected |
◆ timer
rclcpp::TimerBase::SharedPtr wbc_ros::SingleArmController::timer |
|
protected |
◆ timing_stats
TimingStatsMsg wbc_ros::SingleArmController::timing_stats |
|
protected |
◆ timing_stats_publisher
TimingStatsPublisher::SharedPtr wbc_ros::SingleArmController::timing_stats_publisher |
|
protected |
◆ update_rate
int wbc_ros::SingleArmController::update_rate |
|
protected |
The documentation for this class was generated from the following files: