ATRV-JR Node for ROS By Mikhail Medvedev 02/2012 Modified from B21 node originally written by David Lu. More...
Public Member Functions | |
ATRVJRNode () | |
int | initialize (const char *port) |
void | NewCommand (const geometry_msgs::Twist::ConstPtr &msg) |
cmd_vel callback | |
void | SetAcceleration (const std_msgs::Float32::ConstPtr &msg) |
cmd_acceleration callback | |
void | spinOnce () |
void | ToggleBrakePower (const std_msgs::Bool::ConstPtr &msg) |
cmd_brake_power callback | |
void | ToggleSonarPower (const std_msgs::Bool::ConstPtr &msg) |
cmd_sonar_power callback | |
~ATRVJRNode () | |
Public Attributes | |
ros::NodeHandle | n |
Private Member Functions | |
void | publishBumps () |
void | publishOdometry () |
void | publishSonar () |
Private Attributes | |
float | a_odo |
float | acceleration |
ros::Publisher | base_sonar_pub |
Sonar Publisher for Base Sonars (sonar_cloud_base) | |
ros::Publisher | body_sonar_pub |
Sonar Publisher for Body Sonars (sonar_cloud_body) | |
bool | brake_dirty |
ros::Publisher | brake_power_pub |
Brake Power Publisher (brake_power) | |
tf::TransformBroadcaster | broadcaster |
Transform Broadcaster (for odom) | |
ros::Publisher | bump_pub |
Bump Publisher (bumps) | |
float | cmdRotation |
float | cmdTranslation |
ATRVJR | driver |
float | first_bearing |
bool | initialized |
bool | isBrakeOn |
bool | isSonarOn |
ros::Publisher | joint_pub |
Joint State Publisher (state) | |
float | last_bearing |
float | last_distance |
ros::Publisher | odom_pub |
Odometry Publisher (odom) | |
ros::Publisher | plugged_pub |
Plugged In Publisher (plugged_in) | |
int | prev_bumps |
bool | sonar_dirty |
bool | sonar_just_on |
ros::Publisher | sonar_power_pub |
Sonar Power Publisher (sonar_power) | |
ros::Subscriber | subs [4] |
Subscriber handles (cmd_vel, cmd_accel, cmd_sonar_power, cmd_brake_power) | |
int | updateTimer |
ros::Publisher | voltage_pub |
Voltage Publisher (voltage) | |
float | x_odo |
float | y_odo |
ATRV-JR Node for ROS By Mikhail Medvedev 02/2012 Modified from B21 node originally written by David Lu.
This program is free software; you can redistribute it and/or modify it under the terms of the GNU General Public License as published by the Free Software Foundation; either version 2 of the License, or (at your option) any later version.
This program is distributed in the hope that it will be useful, but WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License for more details.
You should have received a copy of the GNU General Public License along with this program; if not, write to the Free Software Foundation, Inc., 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA
Definition at line 33 of file atrvjr_node.cc.
Definition at line 79 of file atrvjr_node.cc.
Definition at line 115 of file atrvjr_node.cc.
int ATRVJRNode::initialize | ( | const char * | port | ) |
Definition at line 104 of file atrvjr_node.cc.
void ATRVJRNode::NewCommand | ( | const geometry_msgs::Twist::ConstPtr & | msg | ) |
cmd_vel callback
Definition at line 124 of file atrvjr_node.cc.
void ATRVJRNode::publishBumps | ( | ) | [private] |
Definition at line 286 of file atrvjr_node.cc.
void ATRVJRNode::publishOdometry | ( | ) | [private] |
Integrates over the lastest raw odometry readings from the driver to get x, y and theta
Definition at line 186 of file atrvjr_node.cc.
void ATRVJRNode::publishSonar | ( | ) | [private] |
Definition at line 266 of file atrvjr_node.cc.
void ATRVJRNode::SetAcceleration | ( | const std_msgs::Float32::ConstPtr & | msg | ) |
cmd_acceleration callback
Definition at line 130 of file atrvjr_node.cc.
void ATRVJRNode::spinOnce | ( | ) |
Definition at line 146 of file atrvjr_node.cc.
void ATRVJRNode::ToggleBrakePower | ( | const std_msgs::Bool::ConstPtr & | msg | ) |
cmd_brake_power callback
Definition at line 141 of file atrvjr_node.cc.
void ATRVJRNode::ToggleSonarPower | ( | const std_msgs::Bool::ConstPtr & | msg | ) |
cmd_sonar_power callback
Definition at line 135 of file atrvjr_node.cc.
float ATRVJRNode::a_odo [private] |
Definition at line 52 of file atrvjr_node.cc.
float ATRVJRNode::acceleration [private] |
Definition at line 50 of file atrvjr_node.cc.
ros::Publisher ATRVJRNode::base_sonar_pub [private] |
Sonar Publisher for Base Sonars (sonar_cloud_base)
Definition at line 38 of file atrvjr_node.cc.
ros::Publisher ATRVJRNode::body_sonar_pub [private] |
Sonar Publisher for Body Sonars (sonar_cloud_body)
Definition at line 39 of file atrvjr_node.cc.
bool ATRVJRNode::brake_dirty [private] |
Definition at line 54 of file atrvjr_node.cc.
ros::Publisher ATRVJRNode::brake_power_pub [private] |
Brake Power Publisher (brake_power)
Definition at line 41 of file atrvjr_node.cc.
Transform Broadcaster (for odom)
Definition at line 47 of file atrvjr_node.cc.
ros::Publisher ATRVJRNode::bump_pub [private] |
Bump Publisher (bumps)
Definition at line 46 of file atrvjr_node.cc.
float ATRVJRNode::cmdRotation [private] |
Definition at line 53 of file atrvjr_node.cc.
float ATRVJRNode::cmdTranslation [private] |
Definition at line 53 of file atrvjr_node.cc.
ATRVJR ATRVJRNode::driver [private] |
Definition at line 35 of file atrvjr_node.cc.
float ATRVJRNode::first_bearing [private] |
Definition at line 56 of file atrvjr_node.cc.
bool ATRVJRNode::initialized [private] |
Definition at line 55 of file atrvjr_node.cc.
bool ATRVJRNode::isBrakeOn [private] |
Definition at line 49 of file atrvjr_node.cc.
bool ATRVJRNode::isSonarOn [private] |
Definition at line 49 of file atrvjr_node.cc.
ros::Publisher ATRVJRNode::joint_pub [private] |
Joint State Publisher (state)
Definition at line 45 of file atrvjr_node.cc.
float ATRVJRNode::last_bearing [private] |
Definition at line 51 of file atrvjr_node.cc.
float ATRVJRNode::last_distance [private] |
Definition at line 51 of file atrvjr_node.cc.
Definition at line 66 of file atrvjr_node.cc.
ros::Publisher ATRVJRNode::odom_pub [private] |
Odometry Publisher (odom)
Definition at line 43 of file atrvjr_node.cc.
ros::Publisher ATRVJRNode::plugged_pub [private] |
Plugged In Publisher (plugged_in)
Definition at line 44 of file atrvjr_node.cc.
int ATRVJRNode::prev_bumps [private] |
Definition at line 58 of file atrvjr_node.cc.
bool ATRVJRNode::sonar_dirty [private] |
Definition at line 54 of file atrvjr_node.cc.
bool ATRVJRNode::sonar_just_on [private] |
Definition at line 59 of file atrvjr_node.cc.
ros::Publisher ATRVJRNode::sonar_power_pub [private] |
Sonar Power Publisher (sonar_power)
Definition at line 42 of file atrvjr_node.cc.
ros::Subscriber ATRVJRNode::subs[4] [private] |
Subscriber handles (cmd_vel, cmd_accel, cmd_sonar_power, cmd_brake_power)
Definition at line 37 of file atrvjr_node.cc.
int ATRVJRNode::updateTimer [private] |
Definition at line 57 of file atrvjr_node.cc.
ros::Publisher ATRVJRNode::voltage_pub [private] |
Voltage Publisher (voltage)
Definition at line 40 of file atrvjr_node.cc.
float ATRVJRNode::x_odo [private] |
Definition at line 52 of file atrvjr_node.cc.
float ATRVJRNode::y_odo [private] |
Definition at line 52 of file atrvjr_node.cc.