Classes | |
class | AdParams |
class | DioParams |
class | JointParams |
Public Member Functions | |
void | spin () |
YpspurRosNode () | |
~YpspurRosNode () | |
Private Types | |
enum | OdometryMode { DIFF, NONE } |
Private Member Functions | |
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) |
Private Attributes | |
const int | ad_num_ = 8 |
std::vector< AdParams > | ads_ |
geometry_msgs::Twist::ConstPtr | cmd_vel_ |
ros::Duration | cmd_vel_expire_ |
ros::Time | cmd_vel_time_ |
int | control_mode_ |
int | device_error_state_ |
int | device_error_state_prev_ |
ros::Time | device_error_state_time_ |
bool | digital_input_enable_ |
unsigned int | dio_dir_ |
unsigned int | dio_dir_default_ |
const int | dio_num_ = 8 |
unsigned int | dio_output_ |
unsigned int | dio_output_default_ |
std::map< int, ros::Time > | dio_revert_ |
std::vector< DioParams > | dios_ |
std::map< std::string, std::string > | frames_ |
std::map< std::string, int > | joint_name_to_num_ |
std::vector< JointParams > | joints_ |
int | key_ |
OdometryMode | mode_ |
ros::NodeHandle | nh_ |
std::string | param_file_ |
std::map< std::string, double > | params_ |
pid_t | pid_ |
ros::NodeHandle | pnh_ |
std::string | port_ |
std::map< std::string, ros::Publisher > | pubs_ |
bool | simulate_ |
bool | simulate_control_ |
std::map< std::string, ros::Subscriber > | subs_ |
tf::TransformBroadcaster | tf_broadcaster_ |
tf::TransformListener | tf_listener_ |
double | tf_time_offset_ |
std::string | ypspur_bin_ |
Definition at line 79 of file ypspur_ros.cpp.
enum YpspurRosNode::OdometryMode [private] |
Definition at line 102 of file ypspur_ros.cpp.
YpspurRosNode::YpspurRosNode | ( | ) | [inline] |
Definition at line 452 of file ypspur_ros.cpp.
YpspurRosNode::~YpspurRosNode | ( | ) | [inline] |
Definition at line 783 of file ypspur_ros.cpp.
void YpspurRosNode::cbAngle | ( | const std_msgs::Float32::ConstPtr & | msg, |
int | num | ||
) | [inline, private] |
Definition at line 282 of file ypspur_ros.cpp.
void YpspurRosNode::cbCmdVel | ( | const geometry_msgs::Twist::ConstPtr & | msg | ) | [inline, private] |
Definition at line 183 of file ypspur_ros.cpp.
void YpspurRosNode::cbControlMode | ( | const ypspur_ros::ControlMode::ConstPtr & | msg | ) | [inline, private] |
Definition at line 168 of file ypspur_ros.cpp.
void YpspurRosNode::cbDigitalOutput | ( | const ypspur_ros::DigitalOutput::ConstPtr & | msg, |
int | id_ | ||
) | [inline, private] |
Definition at line 323 of file ypspur_ros.cpp.
void YpspurRosNode::cbJoint | ( | const trajectory_msgs::JointTrajectory::ConstPtr & | msg | ) | [inline, private] |
Definition at line 192 of file ypspur_ros.cpp.
void YpspurRosNode::cbJointPosition | ( | const ypspur_ros::JointPositionControl::ConstPtr & | msg | ) | [inline, private] |
Definition at line 292 of file ypspur_ros.cpp.
void YpspurRosNode::cbSetAccel | ( | const std_msgs::Float32::ConstPtr & | msg, |
int | num | ||
) | [inline, private] |
Definition at line 261 of file ypspur_ros.cpp.
void YpspurRosNode::cbSetVel | ( | const std_msgs::Float32::ConstPtr & | msg, |
int | num | ||
) | [inline, private] |
Definition at line 251 of file ypspur_ros.cpp.
void YpspurRosNode::cbVel | ( | const std_msgs::Float32::ConstPtr & | msg, |
int | num | ||
) | [inline, private] |
Definition at line 271 of file ypspur_ros.cpp.
void YpspurRosNode::revertDigitalOutput | ( | int | id_ | ) | [inline, private] |
Definition at line 361 of file ypspur_ros.cpp.
void YpspurRosNode::spin | ( | ) | [inline] |
Definition at line 795 of file ypspur_ros.cpp.
void YpspurRosNode::updateDiagnostics | ( | const ros::Time & | now, |
const bool | connection_down = false |
||
) | [inline, private] |
Definition at line 379 of file ypspur_ros.cpp.
const int YpspurRosNode::ad_num_ = 8 [private] |
Definition at line 150 of file ypspur_ros.cpp.
std::vector<AdParams> YpspurRosNode::ads_ [private] |
Definition at line 148 of file ypspur_ros.cpp.
geometry_msgs::Twist::ConstPtr YpspurRosNode::cmd_vel_ [private] |
Definition at line 162 of file ypspur_ros.cpp.
ros::Duration YpspurRosNode::cmd_vel_expire_ [private] |
Definition at line 164 of file ypspur_ros.cpp.
ros::Time YpspurRosNode::cmd_vel_time_ [private] |
Definition at line 163 of file ypspur_ros.cpp.
int YpspurRosNode::control_mode_ [private] |
Definition at line 166 of file ypspur_ros.cpp.
int YpspurRosNode::device_error_state_ [private] |
Definition at line 158 of file ypspur_ros.cpp.
int YpspurRosNode::device_error_state_prev_ [private] |
Definition at line 159 of file ypspur_ros.cpp.
Definition at line 160 of file ypspur_ros.cpp.
bool YpspurRosNode::digital_input_enable_ [private] |
Definition at line 147 of file ypspur_ros.cpp.
unsigned int YpspurRosNode::dio_dir_ [private] |
Definition at line 152 of file ypspur_ros.cpp.
unsigned int YpspurRosNode::dio_dir_default_ [private] |
Definition at line 154 of file ypspur_ros.cpp.
const int YpspurRosNode::dio_num_ = 8 [private] |
Definition at line 155 of file ypspur_ros.cpp.
unsigned int YpspurRosNode::dio_output_ [private] |
Definition at line 151 of file ypspur_ros.cpp.
unsigned int YpspurRosNode::dio_output_default_ [private] |
Definition at line 153 of file ypspur_ros.cpp.
std::map<int, ros::Time> YpspurRosNode::dio_revert_ [private] |
Definition at line 156 of file ypspur_ros.cpp.
std::vector<DioParams> YpspurRosNode::dios_ [private] |
Definition at line 149 of file ypspur_ros.cpp.
std::map<std::string, std::string> YpspurRosNode::frames_ [private] |
Definition at line 92 of file ypspur_ros.cpp.
std::map<std::string, int> YpspurRosNode::joint_name_to_num_ [private] |
Definition at line 129 of file ypspur_ros.cpp.
std::vector<JointParams> YpspurRosNode::joints_ [private] |
Definition at line 128 of file ypspur_ros.cpp.
int YpspurRosNode::key_ [private] |
Definition at line 94 of file ypspur_ros.cpp.
OdometryMode YpspurRosNode::mode_ [private] |
Definition at line 107 of file ypspur_ros.cpp.
ros::NodeHandle YpspurRosNode::nh_ [private] |
Definition at line 82 of file ypspur_ros.cpp.
std::string YpspurRosNode::param_file_ [private] |
Definition at line 90 of file ypspur_ros.cpp.
std::map<std::string, double> YpspurRosNode::params_ [private] |
Definition at line 93 of file ypspur_ros.cpp.
pid_t YpspurRosNode::pid_ [private] |
Definition at line 100 of file ypspur_ros.cpp.
ros::NodeHandle YpspurRosNode::pnh_ [private] |
Definition at line 83 of file ypspur_ros.cpp.
std::string YpspurRosNode::port_ [private] |
Definition at line 89 of file ypspur_ros.cpp.
std::map<std::string, ros::Publisher> YpspurRosNode::pubs_ [private] |
Definition at line 84 of file ypspur_ros.cpp.
bool YpspurRosNode::simulate_ [private] |
Definition at line 95 of file ypspur_ros.cpp.
bool YpspurRosNode::simulate_control_ [private] |
Definition at line 96 of file ypspur_ros.cpp.
std::map<std::string, ros::Subscriber> YpspurRosNode::subs_ [private] |
Definition at line 85 of file ypspur_ros.cpp.
Definition at line 87 of file ypspur_ros.cpp.
Definition at line 86 of file ypspur_ros.cpp.
double YpspurRosNode::tf_time_offset_ [private] |
Definition at line 98 of file ypspur_ros.cpp.
std::string YpspurRosNode::ypspur_bin_ [private] |
Definition at line 91 of file ypspur_ros.cpp.