Container struct. More...
#include <p2os.hpp>
Public Attributes | |
| p2os_msgs::AIO | aio |
| Analog In/Out. | |
| p2os_msgs::BatteryState | batt |
| Provides the battery voltage. | |
| p2os_msgs::DIO | dio |
| Digital In/Out. | |
| p2os_msgs::GripperState | gripper |
| Provides the state of the gripper. | |
| p2os_msgs::MotorState | motors |
| Provides the state of the motors (enabled or disabled) | |
| geometry_msgs::TransformStamped | odom_trans |
| Transformed odometry frame. | |
| nav_msgs::Odometry | position |
| Provides the position of the robot. | |
| p2os_msgs::SonarArray | sonar |
| Container for sonar data. | |
Container struct.
Create a struct that holds the Robot's sensors.
| p2os_msgs::AIO ros_p2os_data::aio |
| p2os_msgs::BatteryState ros_p2os_data::batt |
| p2os_msgs::DIO ros_p2os_data::dio |
| p2os_msgs::GripperState ros_p2os_data::gripper |
| p2os_msgs::MotorState ros_p2os_data::motors |
| geometry_msgs::TransformStamped ros_p2os_data::odom_trans |
| nav_msgs::Odometry ros_p2os_data::position |
| p2os_msgs::SonarArray ros_p2os_data::sonar |