ROS Driver/Wrapper for nav2remote Remote API, implementing standard mobile robot subscribers, publishers, and tf frames as per REP 105. More...
Classes | |
class | BaseOdometry |
Internal class for building and representing the base odometry state. More... | |
struct | Pose2D |
Internal structure for storing pose representation in 2D. More... | |
Public Member Functions | |
Nav2Driver (std::string name) | |
Constructor for driver node. | |
Protected Member Functions | |
void | connect (std::string robot_address, int robot_port) |
Establishes connection to Nav2 base controller on specified IP and port, replacing any existing connection if necessary. Throws std::runtime_error if cannot connect to base controller. | |
void | publishOdometry (bool invert_odom, std::string robot_prefix) |
Retrieves latest odometry information from the base controller, and publishes appropriate message and transforms. | |
void | setVelocity (const geometry_msgs::TwistConstPtr &twist) |
Sets velocity goals for base controller. | |
Private Attributes | |
BaseOdometry | base_odom_ |
ros::Subscriber | cmd_sub_ |
bool | invert_odom_ |
ros::NodeHandle | nh_ |
ros::Timer | odom_loop_ |
ros::Publisher | odom_pub_ |
ros::NodeHandle | private_nh_ |
boost::shared_ptr< Nav2Remote > | remote_ |
std::string | robot_address_ |
int | robot_port_ |
std::string | robot_prefix_ |
tf::TransformBroadcaster | tf_broadcaster_ |
ROS Driver/Wrapper for nav2remote Remote API, implementing standard mobile robot subscribers, publishers, and tf frames as per REP 105.
Definition at line 16 of file nav2_driver.cpp.
nav2_driver::Nav2Driver::Nav2Driver | ( | std::string | name | ) | [inline] |
Constructor for driver node.
name | Name of node |
Definition at line 24 of file nav2_driver.cpp.
void nav2_driver::Nav2Driver::connect | ( | std::string | robot_address, |
int | robot_port | ||
) | [inline, protected] |
Establishes connection to Nav2 base controller on specified IP and port, replacing any existing connection if necessary. Throws std::runtime_error if cannot connect to base controller.
Definition at line 60 of file nav2_driver.cpp.
void nav2_driver::Nav2Driver::publishOdometry | ( | bool | invert_odom, |
std::string | robot_prefix | ||
) | [inline, protected] |
Retrieves latest odometry information from the base controller, and publishes appropriate message and transforms.
invert_odom | Invert odometry for use with robot_pose_ekf |
robot_prefix | Tf prefix to use with odom and base_link frame |
Definition at line 97 of file nav2_driver.cpp.
void nav2_driver::Nav2Driver::setVelocity | ( | const geometry_msgs::TwistConstPtr & | twist | ) | [inline, protected] |
Sets velocity goals for base controller.
twist | Incoming velocity command from ROS |
Definition at line 116 of file nav2_driver.cpp.
Definition at line 293 of file nav2_driver.cpp.
Definition at line 291 of file nav2_driver.cpp.
bool nav2_driver::Nav2Driver::invert_odom_ [private] |
Definition at line 297 of file nav2_driver.cpp.
ros::NodeHandle nav2_driver::Nav2Driver::nh_ [private] |
Definition at line 284 of file nav2_driver.cpp.
Definition at line 292 of file nav2_driver.cpp.
Definition at line 290 of file nav2_driver.cpp.
Definition at line 285 of file nav2_driver.cpp.
boost::shared_ptr<Nav2Remote> nav2_driver::Nav2Driver::remote_ [private] |
Definition at line 288 of file nav2_driver.cpp.
std::string nav2_driver::Nav2Driver::robot_address_ [private] |
Definition at line 295 of file nav2_driver.cpp.
int nav2_driver::Nav2Driver::robot_port_ [private] |
Definition at line 296 of file nav2_driver.cpp.
std::string nav2_driver::Nav2Driver::robot_prefix_ [private] |
Definition at line 295 of file nav2_driver.cpp.
Definition at line 286 of file nav2_driver.cpp.