B21 Node for ROS By David Lu!! 2/2010. More...
Public Member Functions | |
| B21Node () | |
| void | configure (rflex::B21Config &config, uint32_t level) |
| int | initialize (const char *port) |
| void | NewCommand (const geometry_msgs::Twist::ConstPtr &msg) |
| cmd_vel callback | |
| void | produce_diagnostics (diagnostic_updater::DiagnosticStatusWrapper &stat) |
| void | spinOnce () |
| ~B21Node () | |
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 |
| B21 | 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 |
| dynamic_reconfigure::Server < rflex::B21Config > | server |
| Dynamic Reconfigure Server. | |
| bool | sonar_dirty |
| bool | sonar_just_on |
| ros::Publisher | sonar_power_pub |
| Sonar Power Publisher (sonar_power) | |
| ros::Subscriber | sub |
| Subscriber handle for cmd_vel. | |
| diagnostic_updater::Updater | updater |
| int | updateTimer |
| ros::Publisher | voltage_pub |
| Voltage Publisher (voltage) | |
| float | x_odo |
| float | y_odo |
B21 Node for ROS By David Lu!! 2/2010.
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 38 of file b21_node.cc.
| B21Node::B21Node | ( | ) |
Definition at line 86 of file b21_node.cc.
Definition at line 125 of file b21_node.cc.
| void B21Node::configure | ( | rflex::B21Config & | config, |
| uint32_t | level | ||
| ) |
Definition at line 139 of file b21_node.cc.
| int B21Node::initialize | ( | const char * | port | ) |
Definition at line 112 of file b21_node.cc.
| void B21Node::NewCommand | ( | const geometry_msgs::Twist::ConstPtr & | msg | ) |
cmd_vel callback
Definition at line 134 of file b21_node.cc.
Definition at line 304 of file b21_node.cc.
| void B21Node::publishBumps | ( | ) | [private] |
Definition at line 288 of file b21_node.cc.
| void B21Node::publishOdometry | ( | ) | [private] |
Integrates over the lastest raw odometry readings from the driver to get x, y and theta
Definition at line 188 of file b21_node.cc.
| void B21Node::publishSonar | ( | ) | [private] |
Definition at line 268 of file b21_node.cc.
| void B21Node::spinOnce | ( | ) |
Definition at line 147 of file b21_node.cc.
float B21Node::a_odo [private] |
Definition at line 60 of file b21_node.cc.
float B21Node::acceleration [private] |
Definition at line 58 of file b21_node.cc.
ros::Publisher B21Node::base_sonar_pub [private] |
Sonar Publisher for Base Sonars (sonar_cloud_base)
Definition at line 43 of file b21_node.cc.
ros::Publisher B21Node::body_sonar_pub [private] |
Sonar Publisher for Body Sonars (sonar_cloud_body)
Definition at line 44 of file b21_node.cc.
bool B21Node::brake_dirty [private] |
Definition at line 62 of file b21_node.cc.
ros::Publisher B21Node::brake_power_pub [private] |
Brake Power Publisher (brake_power)
Definition at line 46 of file b21_node.cc.
tf::TransformBroadcaster B21Node::broadcaster [private] |
Transform Broadcaster (for odom)
Definition at line 52 of file b21_node.cc.
ros::Publisher B21Node::bump_pub [private] |
Bump Publisher (bumps)
Definition at line 51 of file b21_node.cc.
float B21Node::cmdRotation [private] |
Definition at line 61 of file b21_node.cc.
float B21Node::cmdTranslation [private] |
Definition at line 61 of file b21_node.cc.
B21 B21Node::driver [private] |
Definition at line 40 of file b21_node.cc.
float B21Node::first_bearing [private] |
Definition at line 64 of file b21_node.cc.
bool B21Node::initialized [private] |
Definition at line 63 of file b21_node.cc.
bool B21Node::isBrakeOn [private] |
Definition at line 57 of file b21_node.cc.
bool B21Node::isSonarOn [private] |
Definition at line 57 of file b21_node.cc.
ros::Publisher B21Node::joint_pub [private] |
Joint State Publisher (state)
Definition at line 50 of file b21_node.cc.
float B21Node::last_bearing [private] |
Definition at line 59 of file b21_node.cc.
float B21Node::last_distance [private] |
Definition at line 59 of file b21_node.cc.
Definition at line 74 of file b21_node.cc.
ros::Publisher B21Node::odom_pub [private] |
Odometry Publisher (odom)
Definition at line 48 of file b21_node.cc.
ros::Publisher B21Node::plugged_pub [private] |
Plugged In Publisher (plugged_in)
Definition at line 49 of file b21_node.cc.
int B21Node::prev_bumps [private] |
Definition at line 66 of file b21_node.cc.
dynamic_reconfigure::Server<rflex::B21Config> B21Node::server [private] |
Dynamic Reconfigure Server.
Definition at line 54 of file b21_node.cc.
bool B21Node::sonar_dirty [private] |
Definition at line 62 of file b21_node.cc.
bool B21Node::sonar_just_on [private] |
Definition at line 67 of file b21_node.cc.
ros::Publisher B21Node::sonar_power_pub [private] |
Sonar Power Publisher (sonar_power)
Definition at line 47 of file b21_node.cc.
ros::Subscriber B21Node::sub [private] |
Subscriber handle for cmd_vel.
Definition at line 42 of file b21_node.cc.
diagnostic_updater::Updater B21Node::updater [private] |
Definition at line 55 of file b21_node.cc.
int B21Node::updateTimer [private] |
Definition at line 65 of file b21_node.cc.
ros::Publisher B21Node::voltage_pub [private] |
Voltage Publisher (voltage)
Definition at line 45 of file b21_node.cc.
float B21Node::x_odo [private] |
Definition at line 60 of file b21_node.cc.
float B21Node::y_odo [private] |
Definition at line 60 of file b21_node.cc.