moveit2
The MoveIt Motion Planning Framework for ROS 2.
Classes | Public Member Functions | Protected Attributes | List of all members
moveit_servo::ServoFixture Class Reference

#include <servo_launch_test_common.hpp>

Inheritance diagram for moveit_servo::ServoFixture:
Inheritance graph
[legend]
Collaboration diagram for moveit_servo::ServoFixture:
Collaboration graph
[legend]

Classes

struct  TestParameters
 

Public Member Functions

void SetUp () override
 
 ServoFixture ()
 
void TearDown () override
 
std::string resolveServoTopicName (std::string topic_name)
 
bool setupStartClient ()
 
bool setupPauseClient ()
 
bool setupUnpauseClient ()
 
bool setupControlDimsClient ()
 
bool setupDriftDimsClient ()
 
bool setupCollisionScaleSub ()
 
bool setupCommandSub (const std::string &command_type)
 
bool setupJointStateSub ()
 
void statusCB (const std_msgs::msg::Int8::ConstSharedPtr &msg)
 
void collisionScaleCB (const std_msgs::msg::Float64::ConstSharedPtr &msg)
 
void jointStateCB (const sensor_msgs::msg::JointState::ConstSharedPtr &msg)
 
void trajectoryCommandCB (const trajectory_msgs::msg::JointTrajectory::ConstSharedPtr &msg)
 
void arrayCommandCB (const std_msgs::msg::Float64MultiArray::ConstSharedPtr &msg)
 
StatusCode getLatestStatus ()
 
size_t getNumStatus ()
 
void resetNumStatus ()
 
double getLatestCollisionScale ()
 
size_t getNumCollisionScale ()
 
void resetNumCollisionScale ()
 
sensor_msgs::msg::JointState getLatestJointState ()
 
size_t getNumJointState ()
 
void resetNumJointState ()
 
trajectory_msgs::msg::JointTrajectory getLatestTrajCommand ()
 
std_msgs::msg::Float64MultiArray getLatestArrayCommand ()
 
size_t getNumCommands ()
 
void resetNumCommands ()
 
void watchForStatus (StatusCode code_to_watch_for)
 
bool sawTrackedStatus ()
 
bool start ()
 
bool stop ()
 

Protected Attributes

rclcpp::Node::SharedPtr node_
 
rclcpp::Executor::SharedPtr executor_
 
std::thread executor_thread_
 
std::shared_ptr< const moveit_servo::ServoParametersservo_parameters_
 
std::shared_ptr< const struct TestParameterstest_parameters_
 
rclcpp::Client< std_srvs::srv::Trigger >::SharedPtr client_servo_start_
 
rclcpp::Client< std_srvs::srv::Trigger >::SharedPtr client_servo_stop_
 
rclcpp::Client< std_srvs::srv::Trigger >::SharedPtr client_servo_pause_
 
rclcpp::Client< std_srvs::srv::Trigger >::SharedPtr client_servo_unpause_
 
rclcpp::Client< moveit_msgs::srv::ChangeControlDimensions >::SharedPtr client_change_control_dims_
 
rclcpp::Client< moveit_msgs::srv::ChangeDriftDimensions >::SharedPtr client_change_drift_dims_
 
rclcpp::Publisher< geometry_msgs::msg::TwistStamped >::SharedPtr pub_twist_cmd_
 
rclcpp::Publisher< control_msgs::msg::JointJog >::SharedPtr pub_joint_cmd_
 
rclcpp::Subscription< std_msgs::msg::Int8 >::SharedPtr sub_servo_status_
 
rclcpp::Subscription< std_msgs::msg::Float64 >::SharedPtr sub_collision_scale_
 
rclcpp::Subscription< sensor_msgs::msg::JointState >::SharedPtr sub_joint_state_
 
rclcpp::Subscription< trajectory_msgs::msg::JointTrajectory >::SharedPtr sub_trajectory_cmd_output_
 
rclcpp::Subscription< std_msgs::msg::Float64MultiArray >::SharedPtr sub_array_cmd_output_
 
size_t num_status_
 
StatusCode latest_status_ = StatusCode::NO_WARNING
 
size_t num_collision_scale_
 
double latest_collision_scale_
 
size_t num_joint_state_
 
sensor_msgs::msg::JointState::ConstSharedPtr latest_joint_state_
 
size_t num_commands_
 
trajectory_msgs::msg::JointTrajectory::ConstSharedPtr latest_traj_cmd_
 
std_msgs::msg::Float64MultiArray::ConstSharedPtr latest_array_cmd_
 
bool status_seen_
 
StatusCode status_tracking_code_ = StatusCode::NO_WARNING
 
std::mutex latest_state_mutex_
 

Detailed Description

Definition at line 70 of file servo_launch_test_common.hpp.

Constructor & Destructor Documentation

◆ ServoFixture()

moveit_servo::ServoFixture::ServoFixture ( )
inline

Definition at line 80 of file servo_launch_test_common.hpp.

Here is the call graph for this function:

Member Function Documentation

◆ arrayCommandCB()

void moveit_servo::ServoFixture::arrayCommandCB ( const std_msgs::msg::Float64MultiArray::ConstSharedPtr &  msg)
inline

Definition at line 302 of file servo_launch_test_common.hpp.

Here is the caller graph for this function:

◆ collisionScaleCB()

void moveit_servo::ServoFixture::collisionScaleCB ( const std_msgs::msg::Float64::ConstSharedPtr &  msg)
inline

Definition at line 281 of file servo_launch_test_common.hpp.

Here is the caller graph for this function:

◆ getLatestArrayCommand()

std_msgs::msg::Float64MultiArray moveit_servo::ServoFixture::getLatestArrayCommand ( )
inline

Definition at line 369 of file servo_launch_test_common.hpp.

◆ getLatestCollisionScale()

double moveit_servo::ServoFixture::getLatestCollisionScale ( )
inline

Definition at line 327 of file servo_launch_test_common.hpp.

◆ getLatestJointState()

sensor_msgs::msg::JointState moveit_servo::ServoFixture::getLatestJointState ( )
inline

Definition at line 345 of file servo_launch_test_common.hpp.

◆ getLatestStatus()

StatusCode moveit_servo::ServoFixture::getLatestStatus ( )
inline

Definition at line 309 of file servo_launch_test_common.hpp.

◆ getLatestTrajCommand()

trajectory_msgs::msg::JointTrajectory moveit_servo::ServoFixture::getLatestTrajCommand ( )
inline

Definition at line 363 of file servo_launch_test_common.hpp.

◆ getNumCollisionScale()

size_t moveit_servo::ServoFixture::getNumCollisionScale ( )
inline

Definition at line 333 of file servo_launch_test_common.hpp.

◆ getNumCommands()

size_t moveit_servo::ServoFixture::getNumCommands ( )
inline

Definition at line 375 of file servo_launch_test_common.hpp.

◆ getNumJointState()

size_t moveit_servo::ServoFixture::getNumJointState ( )
inline

Definition at line 351 of file servo_launch_test_common.hpp.

◆ getNumStatus()

size_t moveit_servo::ServoFixture::getNumStatus ( )
inline

Definition at line 315 of file servo_launch_test_common.hpp.

◆ jointStateCB()

void moveit_servo::ServoFixture::jointStateCB ( const sensor_msgs::msg::JointState::ConstSharedPtr &  msg)
inline

Definition at line 288 of file servo_launch_test_common.hpp.

Here is the caller graph for this function:

◆ resetNumCollisionScale()

void moveit_servo::ServoFixture::resetNumCollisionScale ( )
inline

Definition at line 339 of file servo_launch_test_common.hpp.

◆ resetNumCommands()

void moveit_servo::ServoFixture::resetNumCommands ( )
inline

Definition at line 381 of file servo_launch_test_common.hpp.

◆ resetNumJointState()

void moveit_servo::ServoFixture::resetNumJointState ( )
inline

Definition at line 357 of file servo_launch_test_common.hpp.

◆ resetNumStatus()

void moveit_servo::ServoFixture::resetNumStatus ( )
inline

Definition at line 321 of file servo_launch_test_common.hpp.

◆ resolveServoTopicName()

std::string moveit_servo::ServoFixture::resolveServoTopicName ( std::string  topic_name)
inline

Definition at line 123 of file servo_launch_test_common.hpp.

Here is the caller graph for this function:

◆ sawTrackedStatus()

bool moveit_servo::ServoFixture::sawTrackedStatus ( )
inline

Definition at line 394 of file servo_launch_test_common.hpp.

◆ SetUp()

void moveit_servo::ServoFixture::SetUp ( )
inlineoverride

Definition at line 73 of file servo_launch_test_common.hpp.

◆ setupCollisionScaleSub()

bool moveit_servo::ServoFixture::setupCollisionScaleSub ( )
inline

Definition at line 233 of file servo_launch_test_common.hpp.

Here is the call graph for this function:

◆ setupCommandSub()

bool moveit_servo::ServoFixture::setupCommandSub ( const std::string &  command_type)
inline

Definition at line 241 of file servo_launch_test_common.hpp.

Here is the call graph for this function:

◆ setupControlDimsClient()

bool moveit_servo::ServoFixture::setupControlDimsClient ( )
inline

Definition at line 199 of file servo_launch_test_common.hpp.

Here is the call graph for this function:

◆ setupDriftDimsClient()

bool moveit_servo::ServoFixture::setupDriftDimsClient ( )
inline

Definition at line 216 of file servo_launch_test_common.hpp.

Here is the call graph for this function:

◆ setupJointStateSub()

bool moveit_servo::ServoFixture::setupJointStateSub ( )
inline

Definition at line 264 of file servo_launch_test_common.hpp.

Here is the call graph for this function:

◆ setupPauseClient()

bool moveit_servo::ServoFixture::setupPauseClient ( )
inline

Definition at line 167 of file servo_launch_test_common.hpp.

Here is the call graph for this function:

◆ setupStartClient()

bool moveit_servo::ServoFixture::setupStartClient ( )
inline

Definition at line 132 of file servo_launch_test_common.hpp.

Here is the call graph for this function:

◆ setupUnpauseClient()

bool moveit_servo::ServoFixture::setupUnpauseClient ( )
inline

Definition at line 183 of file servo_launch_test_common.hpp.

Here is the call graph for this function:

◆ start()

bool moveit_servo::ServoFixture::start ( )
inline

Definition at line 400 of file servo_launch_test_common.hpp.

◆ statusCB()

void moveit_servo::ServoFixture::statusCB ( const std_msgs::msg::Int8::ConstSharedPtr &  msg)
inline

Definition at line 272 of file servo_launch_test_common.hpp.

◆ stop()

bool moveit_servo::ServoFixture::stop ( )
inline

Definition at line 432 of file servo_launch_test_common.hpp.

Here is the caller graph for this function:

◆ TearDown()

void moveit_servo::ServoFixture::TearDown ( )
inlineoverride

Definition at line 110 of file servo_launch_test_common.hpp.

Here is the call graph for this function:

◆ trajectoryCommandCB()

void moveit_servo::ServoFixture::trajectoryCommandCB ( const trajectory_msgs::msg::JointTrajectory::ConstSharedPtr &  msg)
inline

Definition at line 295 of file servo_launch_test_common.hpp.

Here is the caller graph for this function:

◆ watchForStatus()

void moveit_servo::ServoFixture::watchForStatus ( StatusCode  code_to_watch_for)
inline

Definition at line 387 of file servo_launch_test_common.hpp.

Member Data Documentation

◆ client_change_control_dims_

rclcpp::Client<moveit_msgs::srv::ChangeControlDimensions>::SharedPtr moveit_servo::ServoFixture::client_change_control_dims_
protected

Definition at line 466 of file servo_launch_test_common.hpp.

◆ client_change_drift_dims_

rclcpp::Client<moveit_msgs::srv::ChangeDriftDimensions>::SharedPtr moveit_servo::ServoFixture::client_change_drift_dims_
protected

Definition at line 467 of file servo_launch_test_common.hpp.

◆ client_servo_pause_

rclcpp::Client<std_srvs::srv::Trigger>::SharedPtr moveit_servo::ServoFixture::client_servo_pause_
protected

Definition at line 464 of file servo_launch_test_common.hpp.

◆ client_servo_start_

rclcpp::Client<std_srvs::srv::Trigger>::SharedPtr moveit_servo::ServoFixture::client_servo_start_
protected

Definition at line 462 of file servo_launch_test_common.hpp.

◆ client_servo_stop_

rclcpp::Client<std_srvs::srv::Trigger>::SharedPtr moveit_servo::ServoFixture::client_servo_stop_
protected

Definition at line 463 of file servo_launch_test_common.hpp.

◆ client_servo_unpause_

rclcpp::Client<std_srvs::srv::Trigger>::SharedPtr moveit_servo::ServoFixture::client_servo_unpause_
protected

Definition at line 465 of file servo_launch_test_common.hpp.

◆ executor_

rclcpp::Executor::SharedPtr moveit_servo::ServoFixture::executor_
protected

Definition at line 446 of file servo_launch_test_common.hpp.

◆ executor_thread_

std::thread moveit_servo::ServoFixture::executor_thread_
protected

Definition at line 447 of file servo_launch_test_common.hpp.

◆ latest_array_cmd_

std_msgs::msg::Float64MultiArray::ConstSharedPtr moveit_servo::ServoFixture::latest_array_cmd_
protected

Definition at line 492 of file servo_launch_test_common.hpp.

◆ latest_collision_scale_

double moveit_servo::ServoFixture::latest_collision_scale_
protected

Definition at line 485 of file servo_launch_test_common.hpp.

◆ latest_joint_state_

sensor_msgs::msg::JointState::ConstSharedPtr moveit_servo::ServoFixture::latest_joint_state_
protected

Definition at line 488 of file servo_launch_test_common.hpp.

◆ latest_state_mutex_

std::mutex moveit_servo::ServoFixture::latest_state_mutex_
mutableprotected

Definition at line 497 of file servo_launch_test_common.hpp.

◆ latest_status_

StatusCode moveit_servo::ServoFixture::latest_status_ = StatusCode::NO_WARNING
protected

Definition at line 482 of file servo_launch_test_common.hpp.

◆ latest_traj_cmd_

trajectory_msgs::msg::JointTrajectory::ConstSharedPtr moveit_servo::ServoFixture::latest_traj_cmd_
protected

Definition at line 491 of file servo_launch_test_common.hpp.

◆ node_

rclcpp::Node::SharedPtr moveit_servo::ServoFixture::node_
protected

Definition at line 445 of file servo_launch_test_common.hpp.

◆ num_collision_scale_

size_t moveit_servo::ServoFixture::num_collision_scale_
protected

Definition at line 484 of file servo_launch_test_common.hpp.

◆ num_commands_

size_t moveit_servo::ServoFixture::num_commands_
protected

Definition at line 490 of file servo_launch_test_common.hpp.

◆ num_joint_state_

size_t moveit_servo::ServoFixture::num_joint_state_
protected

Definition at line 487 of file servo_launch_test_common.hpp.

◆ num_status_

size_t moveit_servo::ServoFixture::num_status_
protected

Definition at line 481 of file servo_launch_test_common.hpp.

◆ pub_joint_cmd_

rclcpp::Publisher<control_msgs::msg::JointJog>::SharedPtr moveit_servo::ServoFixture::pub_joint_cmd_
protected

Definition at line 471 of file servo_launch_test_common.hpp.

◆ pub_twist_cmd_

rclcpp::Publisher<geometry_msgs::msg::TwistStamped>::SharedPtr moveit_servo::ServoFixture::pub_twist_cmd_
protected

Definition at line 470 of file servo_launch_test_common.hpp.

◆ servo_parameters_

std::shared_ptr<const moveit_servo::ServoParameters> moveit_servo::ServoFixture::servo_parameters_
protected

Definition at line 448 of file servo_launch_test_common.hpp.

◆ status_seen_

bool moveit_servo::ServoFixture::status_seen_
protected

Definition at line 494 of file servo_launch_test_common.hpp.

◆ status_tracking_code_

StatusCode moveit_servo::ServoFixture::status_tracking_code_ = StatusCode::NO_WARNING
protected

Definition at line 495 of file servo_launch_test_common.hpp.

◆ sub_array_cmd_output_

rclcpp::Subscription<std_msgs::msg::Float64MultiArray>::SharedPtr moveit_servo::ServoFixture::sub_array_cmd_output_
protected

Definition at line 478 of file servo_launch_test_common.hpp.

◆ sub_collision_scale_

rclcpp::Subscription<std_msgs::msg::Float64>::SharedPtr moveit_servo::ServoFixture::sub_collision_scale_
protected

Definition at line 475 of file servo_launch_test_common.hpp.

◆ sub_joint_state_

rclcpp::Subscription<sensor_msgs::msg::JointState>::SharedPtr moveit_servo::ServoFixture::sub_joint_state_
protected

Definition at line 476 of file servo_launch_test_common.hpp.

◆ sub_servo_status_

rclcpp::Subscription<std_msgs::msg::Int8>::SharedPtr moveit_servo::ServoFixture::sub_servo_status_
protected

Definition at line 474 of file servo_launch_test_common.hpp.

◆ sub_trajectory_cmd_output_

rclcpp::Subscription<trajectory_msgs::msg::JointTrajectory>::SharedPtr moveit_servo::ServoFixture::sub_trajectory_cmd_output_
protected

Definition at line 477 of file servo_launch_test_common.hpp.

◆ test_parameters_

std::shared_ptr<const struct TestParameters> moveit_servo::ServoFixture::test_parameters_
protected

Definition at line 457 of file servo_launch_test_common.hpp.


The documentation for this class was generated from the following file: