Public Member Functions | Protected Member Functions | Protected Attributes
RosAriaNode Class Reference

Node that interfaces between ROS and mobile robot base features via ARIA library. More...

List of all members.

Public Member Functions

void cmdvel_cb (const geometry_msgs::TwistConstPtr &)
void cmdvel_watchdog (const ros::TimerEvent &event)
void dynamic_reconfigureCB (rosaria::RosAriaConfig &config, uint32_t level)
void publish ()
void readParameters ()
 RosAriaNode (ros::NodeHandle n)
int Setup ()
void sonarConnectCb ()
 Called when another node subscribes or unsubscribes from sonar topic.
void spin ()
virtual ~RosAriaNode ()

Protected Member Functions

bool disable_motors_cb (std_srvs::Empty::Request &request, std_srvs::Empty::Response &response)
bool enable_motors_cb (std_srvs::Empty::Request &request, std_srvs::Empty::Response &response)

Protected Attributes

std::string aria_log_filename
rosaria::BumperState bumpers
ros::Publisher bumpers_pub
ros::Subscriber cmdvel_sub
ros::Duration cmdvel_timeout
ros::Timer cmdvel_watchdog_timer
ArRobotConnector * conn
bool debug_aria
ros::ServiceServer disable_srv
int DriftFactor
dynamic_reconfigure::Server
< rosaria::RosAriaConfig > * 
dynamic_reconfigure_server
ros::ServiceServer enable_srv
std::string frame_id_base_link
std::string frame_id_bumper
std::string frame_id_odom
std::string frame_id_sonar
ArLaserConnector * laserConnector
std_msgs::Bool motors_state
ros::Publisher motors_state_pub
ArFunctorC< RosAriaNodemyPublishCB
ros::NodeHandle n
tf::TransformBroadcaster odom_broadcaster
geometry_msgs::TransformStamped odom_trans
ArPose pos
ros::Publisher pose_pub
nav_msgs::Odometry position
bool publish_aria_lasers
bool publish_sonar
bool publish_sonar_pointcloud2
bool published_motors_state
std_msgs::Int8 recharge_state
ros::Publisher recharge_state_pub
int RevCount
ArRobot * robot
int serial_baud
std::string serial_port
bool sonar_enabled
ros::Publisher sonar_pointcloud2_pub
ros::Publisher sonar_pub
ros::Publisher state_of_charge_pub
int TicksMM
ros::Time veltime
ros::Publisher voltage_pub

Detailed Description

Node that interfaces between ROS and mobile robot base features via ARIA library.

RosAriaNode will use ARIA to connect to a robot controller (configure via ~port parameter), either direct serial connection or over the network. It runs ARIA's robot communications cycle in a background thread, and as part of that cycle (a sensor interpretation task which calls RosAriaNode::publish()), it publishes various topics with newly received robot data. It also sends velocity commands to the robot when received in the cmd_vel topic, and handles dynamic_reconfigure and Service requests.

For more information about ARIA see http://robots.mobilerobots.com/wiki/Aria.

RosAria uses the roscpp client library, see http://www.ros.org/wiki/roscpp for information, tutorials and documentation.

Definition at line 50 of file RosAria.cpp.


Constructor & Destructor Documentation

Definition at line 279 of file RosAria.cpp.

Definition at line 342 of file RosAria.cpp.


Member Function Documentation

void RosAriaNode::cmdvel_cb ( const geometry_msgs::TwistConstPtr &  msg)

Definition at line 718 of file RosAria.cpp.

Definition at line 733 of file RosAria.cpp.

bool RosAriaNode::disable_motors_cb ( std_srvs::Empty::Request &  request,
std_srvs::Empty::Response &  response 
) [protected]

Definition at line 707 of file RosAria.cpp.

void RosAriaNode::dynamic_reconfigureCB ( rosaria::RosAriaConfig &  config,
uint32_t  level 
)

Definition at line 183 of file RosAria.cpp.

bool RosAriaNode::enable_motors_cb ( std_srvs::Empty::Request &  request,
std_srvs::Empty::Response &  response 
) [protected]

Definition at line 695 of file RosAria.cpp.

Definition at line 532 of file RosAria.cpp.

Definition at line 138 of file RosAria.cpp.

Definition at line 353 of file RosAria.cpp.

Called when another node subscribes or unsubscribes from sonar topic.

Definition at line 261 of file RosAria.cpp.

Definition at line 527 of file RosAria.cpp.


Member Data Documentation

std::string RosAriaNode::aria_log_filename [protected]

Definition at line 126 of file RosAria.cpp.

rosaria::BumperState RosAriaNode::bumpers [protected]

Definition at line 103 of file RosAria.cpp.

Definition at line 71 of file RosAria.cpp.

Definition at line 85 of file RosAria.cpp.

Definition at line 94 of file RosAria.cpp.

Definition at line 93 of file RosAria.cpp.

ArRobotConnector* RosAriaNode::conn [protected]

Definition at line 99 of file RosAria.cpp.

bool RosAriaNode::debug_aria [protected]

Definition at line 125 of file RosAria.cpp.

Definition at line 88 of file RosAria.cpp.

int RosAriaNode::DriftFactor [protected]

Definition at line 129 of file RosAria.cpp.

dynamic_reconfigure::Server<rosaria::RosAriaConfig>* RosAriaNode::dynamic_reconfigure_server [protected]

Definition at line 132 of file RosAria.cpp.

Definition at line 87 of file RosAria.cpp.

std::string RosAriaNode::frame_id_base_link [protected]

Definition at line 113 of file RosAria.cpp.

std::string RosAriaNode::frame_id_bumper [protected]

Definition at line 114 of file RosAria.cpp.

std::string RosAriaNode::frame_id_odom [protected]

Definition at line 112 of file RosAria.cpp.

std::string RosAriaNode::frame_id_sonar [protected]

Definition at line 115 of file RosAria.cpp.

ArLaserConnector* RosAriaNode::laserConnector [protected]

Definition at line 100 of file RosAria.cpp.

std_msgs::Bool RosAriaNode::motors_state [protected]

Definition at line 82 of file RosAria.cpp.

Definition at line 81 of file RosAria.cpp.

ArFunctorC<RosAriaNode> RosAriaNode::myPublishCB [protected]

Definition at line 105 of file RosAria.cpp.

Definition at line 69 of file RosAria.cpp.

Definition at line 109 of file RosAria.cpp.

geometry_msgs::TransformStamped RosAriaNode::odom_trans [protected]

Definition at line 110 of file RosAria.cpp.

ArPose RosAriaNode::pos [protected]

Definition at line 104 of file RosAria.cpp.

Definition at line 70 of file RosAria.cpp.

nav_msgs::Odometry RosAriaNode::position [protected]

Definition at line 102 of file RosAria.cpp.

Definition at line 135 of file RosAria.cpp.

bool RosAriaNode::publish_sonar [protected]

Definition at line 121 of file RosAria.cpp.

Definition at line 122 of file RosAria.cpp.

Definition at line 83 of file RosAria.cpp.

std_msgs::Int8 RosAriaNode::recharge_state [protected]

Definition at line 77 of file RosAria.cpp.

Definition at line 76 of file RosAria.cpp.

int RosAriaNode::RevCount [protected]

Definition at line 129 of file RosAria.cpp.

ArRobot* RosAriaNode::robot [protected]

Definition at line 101 of file RosAria.cpp.

int RosAriaNode::serial_baud [protected]

Definition at line 97 of file RosAria.cpp.

std::string RosAriaNode::serial_port [protected]

Definition at line 96 of file RosAria.cpp.

bool RosAriaNode::sonar_enabled [protected]

Definition at line 118 of file RosAria.cpp.

Definition at line 73 of file RosAria.cpp.

Definition at line 72 of file RosAria.cpp.

Definition at line 79 of file RosAria.cpp.

int RosAriaNode::TicksMM [protected]

Definition at line 129 of file RosAria.cpp.

Definition at line 92 of file RosAria.cpp.

Definition at line 74 of file RosAria.cpp.


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


rosaria
Author(s): Srećko Jurić-Kavelj
autogenerated on Thu Jun 6 2019 22:00:56