|  | 
| void | cbAngle (const std_msgs::Float32::ConstPtr &msg, int num) | 
|  | 
| void | cbCmdVel (const geometry_msgs::Twist::ConstPtr &msg) | 
|  | 
| void | cbControlMode (const ypspur_ros::ControlMode::ConstPtr &msg) | 
|  | 
| void | cbDigitalOutput (const ypspur_ros::DigitalOutput::ConstPtr &msg, int id_) | 
|  | 
| void | cbJoint (const trajectory_msgs::JointTrajectory::ConstPtr &msg) | 
|  | 
| void | cbJointPosition (const ypspur_ros::JointPositionControl::ConstPtr &msg) | 
|  | 
| void | cbSetAccel (const std_msgs::Float32::ConstPtr &msg, int num) | 
|  | 
| void | cbSetVel (const std_msgs::Float32::ConstPtr &msg, int num) | 
|  | 
| void | cbVel (const std_msgs::Float32::ConstPtr &msg, int num) | 
|  | 
| void | revertDigitalOutput (int id_) | 
|  | 
| void | updateDiagnostics (const ros::Time &now, const bool connection_down=false) | 
|  | 
Definition at line 81 of file ypspur_ros.cpp.
 
  
  | 
        
          | YpspurRosNode::YpspurRosNode | ( |  | ) |  |  | inline | 
 
 
  
  | 
        
          | YpspurRosNode::~YpspurRosNode | ( |  | ) |  |  | inline | 
 
 
  
  | 
        
          | void YpspurRosNode::cbAngle | ( | const std_msgs::Float32::ConstPtr & | msg, |  
          |  |  | int | num |  
          |  | ) |  |  |  | inlineprivate | 
 
 
  
  | 
        
          | void YpspurRosNode::cbCmdVel | ( | const geometry_msgs::Twist::ConstPtr & | msg | ) |  |  | inlineprivate | 
 
 
  
  | 
        
          | void YpspurRosNode::cbControlMode | ( | const ypspur_ros::ControlMode::ConstPtr & | msg | ) |  |  | inlineprivate | 
 
 
  
  | 
        
          | void YpspurRosNode::cbDigitalOutput | ( | const ypspur_ros::DigitalOutput::ConstPtr & | msg, |  
          |  |  | int | id_ |  
          |  | ) |  |  |  | inlineprivate | 
 
 
  
  | 
        
          | void YpspurRosNode::cbJoint | ( | const trajectory_msgs::JointTrajectory::ConstPtr & | msg | ) |  |  | inlineprivate | 
 
 
  
  | 
        
          | void YpspurRosNode::cbJointPosition | ( | const ypspur_ros::JointPositionControl::ConstPtr & | msg | ) |  |  | inlineprivate | 
 
 
  
  | 
        
          | void YpspurRosNode::cbSetAccel | ( | const std_msgs::Float32::ConstPtr & | msg, |  
          |  |  | int | num |  
          |  | ) |  |  |  | inlineprivate | 
 
 
  
  | 
        
          | void YpspurRosNode::cbSetVel | ( | const std_msgs::Float32::ConstPtr & | msg, |  
          |  |  | int | num |  
          |  | ) |  |  |  | inlineprivate | 
 
 
  
  | 
        
          | void YpspurRosNode::cbVel | ( | const std_msgs::Float32::ConstPtr & | msg, |  
          |  |  | int | num |  
          |  | ) |  |  |  | inlineprivate | 
 
 
  
  | 
        
          | void YpspurRosNode::revertDigitalOutput | ( | int | id_ | ) |  |  | inlineprivate | 
 
 
  
  | 
        
          | bool YpspurRosNode::spin | ( |  | ) |  |  | inline | 
 
 
  
  | 
        
          | void YpspurRosNode::updateDiagnostics | ( | const ros::Time & | now, |  
          |  |  | const bool | connection_down = false |  
          |  | ) |  |  |  | inlineprivate | 
 
 
  
  | 
        
          | const int YpspurRosNode::ad_num_ = 8 |  | private | 
 
 
  
  | 
        
          | std::vector<AdParams> YpspurRosNode::ads_ |  | private | 
 
 
  
  | 
        
          | geometry_msgs::Twist::ConstPtr YpspurRosNode::cmd_vel_ |  | private | 
 
 
  
  | 
        
          | int YpspurRosNode::control_mode_ |  | private | 
 
 
  
  | 
        
          | int YpspurRosNode::device_error_state_ |  | private | 
 
 
  
  | 
        
          | int YpspurRosNode::device_error_state_prev_ |  | private | 
 
 
  
  | 
        
          | ros::Time YpspurRosNode::device_error_state_time_ |  | private | 
 
 
  
  | 
        
          | bool YpspurRosNode::digital_input_enable_ |  | private | 
 
 
  
  | 
        
          | unsigned int YpspurRosNode::dio_dir_ |  | private | 
 
 
  
  | 
        
          | unsigned int YpspurRosNode::dio_dir_default_ |  | private | 
 
 
  
  | 
        
          | const int YpspurRosNode::dio_num_ = 8 |  | private | 
 
 
  
  | 
        
          | unsigned int YpspurRosNode::dio_output_ |  | private | 
 
 
  
  | 
        
          | unsigned int YpspurRosNode::dio_output_default_ |  | private | 
 
 
  
  | 
        
          | std::map<int, ros::Time> YpspurRosNode::dio_revert_ |  | private | 
 
 
  
  | 
        
          | std::map<std::string, std::string> YpspurRosNode::frames_ |  | private | 
 
 
  
  | 
        
          | std::map<std::string, int> YpspurRosNode::joint_name_to_num_ |  | private | 
 
 
  
  | 
        
          | std::string YpspurRosNode::param_file_ |  | private | 
 
 
  
  | 
        
          | std::map<std::string, double> YpspurRosNode::params_ |  | private | 
 
 
  
  | 
        
          | pid_t YpspurRosNode::pid_ |  | private | 
 
 
  
  | 
        
          | std::string YpspurRosNode::port_ |  | private | 
 
 
  
  | 
        
          | bool YpspurRosNode::simulate_ |  | private | 
 
 
  
  | 
        
          | bool YpspurRosNode::simulate_control_ |  | private | 
 
 
  
  | 
        
          | double YpspurRosNode::tf_time_offset_ |  | private | 
 
 
  
  | 
        
          | std::string YpspurRosNode::ypspur_bin_ |  | private | 
 
 
  
  | 
        
          | const tf2::Vector3 YpspurRosNode::z_axis_ |  | private | 
 
 
The documentation for this class was generated from the following file: