#include <servo_ros_fixture.hpp>
Definition at line 55 of file servo_ros_fixture.hpp.
◆ ServoRosFixture()
| ServoRosFixture::ServoRosFixture |
( |
| ) |
|
|
inlineprotected |
◆ jointStateCallback()
| void ServoRosFixture::jointStateCallback |
( |
const sensor_msgs::msg::JointState::ConstSharedPtr & |
msg | ) |
|
|
inlineprotected |
◆ SetUp()
| void ServoRosFixture::SetUp |
( |
| ) |
|
|
inlineoverrideprotected |
◆ statusCallback()
| void ServoRosFixture::statusCallback |
( |
const moveit_msgs::msg::ServoStatus::ConstSharedPtr & |
msg | ) |
|
|
inlineprotected |
◆ TearDown()
| void ServoRosFixture::TearDown |
( |
| ) |
|
|
inlineoverrideprotected |
◆ trajectoryCallback()
| void ServoRosFixture::trajectoryCallback |
( |
const trajectory_msgs::msg::JointTrajectory::ConstSharedPtr & |
msg | ) |
|
|
inlineprotected |
◆ waitForJointStates()
| void ServoRosFixture::waitForJointStates |
( |
| ) |
|
|
inlineprotected |
◆ waitForService()
| void ServoRosFixture::waitForService |
( |
| ) |
|
|
inlineprotected |
◆ executor_
| rclcpp::executors::SingleThreadedExecutor ServoRosFixture::executor_ |
|
protected |
◆ executor_thread_
| std::thread ServoRosFixture::executor_thread_ |
|
protected |
◆ joint_state_subscriber_
| rclcpp::Subscription<sensor_msgs::msg::JointState>::SharedPtr ServoRosFixture::joint_state_subscriber_ |
|
protected |
◆ joint_states_
| sensor_msgs::msg::JointState ServoRosFixture::joint_states_ |
|
protected |
◆ published_trajectory_
| trajectory_msgs::msg::JointTrajectory ServoRosFixture::published_trajectory_ |
|
protected |
◆ servo_test_node_
| std::shared_ptr<rclcpp::Node> ServoRosFixture::servo_test_node_ |
|
protected |
◆ state_count_
| std::atomic<int> ServoRosFixture::state_count_ |
|
protected |
◆ status_
◆ status_count_
| std::atomic<int> ServoRosFixture::status_count_ |
|
protected |
◆ status_subscriber_
| rclcpp::Subscription<moveit_msgs::msg::ServoStatus>::SharedPtr ServoRosFixture::status_subscriber_ |
|
protected |
◆ switch_input_client_
| rclcpp::Client<moveit_msgs::srv::ServoCommandType>::SharedPtr ServoRosFixture::switch_input_client_ |
|
protected |
◆ traj_count_
| std::atomic<int> ServoRosFixture::traj_count_ |
|
protected |
◆ trajectory_subscriber_
| rclcpp::Subscription<trajectory_msgs::msg::JointTrajectory>::SharedPtr ServoRosFixture::trajectory_subscriber_ |
|
protected |
The documentation for this class was generated from the following file: