Public Member Functions | Private Attributes | List of all members
JointOperator Class Reference

#include <joint_operator.h>

Public Member Functions

bool getTrajectoryInfo (const std::string yaml_file, trajectory_msgs::JointTrajectory *jnt_tra_msg)
 
bool isLoop (void)
 
 JointOperator ()
 
bool moveCommandMsgCallback (std_srvs::Trigger::Request &req, std_srvs::Trigger::Response &res)
 
 ~JointOperator ()
 

Private Attributes

bool is_loop_
 
trajectory_msgs::JointTrajectory * jnt_tra_msg_
 
ros::Publisher joint_trajectory_pub_
 
ros::ServiceServer move_command_server_
 
ros::NodeHandle node_handle_
 
ros::NodeHandle priv_node_handle_
 

Detailed Description

Definition at line 30 of file joint_operator.h.

Constructor & Destructor Documentation

JointOperator::JointOperator ( )

Definition at line 21 of file joint_operator.cpp.

JointOperator::~JointOperator ( )

Definition at line 42 of file joint_operator.cpp.

Member Function Documentation

bool JointOperator::getTrajectoryInfo ( const std::string  yaml_file,
trajectory_msgs::JointTrajectory *  jnt_tra_msg 
)

Definition at line 46 of file joint_operator.cpp.

bool JointOperator::isLoop ( void  )
inline

Definition at line 56 of file joint_operator.h.

bool JointOperator::moveCommandMsgCallback ( std_srvs::Trigger::Request &  req,
std_srvs::Trigger::Response &  res 
)

Definition at line 101 of file joint_operator.cpp.

Member Data Documentation

bool JointOperator::is_loop_
private

Definition at line 50 of file joint_operator.h.

trajectory_msgs::JointTrajectory* JointOperator::jnt_tra_msg_
private

Definition at line 49 of file joint_operator.h.

ros::Publisher JointOperator::joint_trajectory_pub_
private

Definition at line 40 of file joint_operator.h.

ros::ServiceServer JointOperator::move_command_server_
private

Definition at line 45 of file joint_operator.h.

ros::NodeHandle JointOperator::node_handle_
private

Definition at line 34 of file joint_operator.h.

ros::NodeHandle JointOperator::priv_node_handle_
private

Definition at line 35 of file joint_operator.h.


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


dynamixel_workbench_operators
Author(s): Darby Lim , Ryan Shim
autogenerated on Mon Sep 28 2020 03:37:04