#include "ca_msgs/ChargingState.h"
#include "ca_msgs/Mode.h"
#include "ca_msgs/Bumper.h"
#include "ca_msgs/DefineSong.h"
#include "ca_msgs/PlaySong.h"
#include "create/create.h"
#include <diagnostic_updater/diagnostic_updater.h>
#include <geometry_msgs/TransformStamped.h>
#include <geometry_msgs/Twist.h>
#include <nav_msgs/Odometry.h>
#include <ros/ros.h>
#include <sensor_msgs/JointState.h>
#include <std_msgs/Bool.h>
#include <std_msgs/Empty.h>
#include <std_msgs/Float32.h>
#include <std_msgs/Int16.h>
#include <std_msgs/UInt16.h>
#include <std_msgs/UInt8MultiArray.h>
#include <tf/transform_broadcaster.h>
#include <limits>
#include <string>
Go to the source code of this file.
Classes | |
class | CreateDriver |
Variables | |
static const double | COVARIANCE [36] |
static const double | MAX_DBL = std::numeric_limits<double>::max() |
Software License Agreement (BSD)
Definition in file create_driver.h.
const double COVARIANCE[36] [static] |
{1e-5, 1e-5, 0.0, 0.0, 0.0, 1e-5, 1e-5, 1e-5, 0.0, 0.0, 0.0, 1e-5, 0.0, 0.0, MAX_DBL, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, MAX_DBL, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, MAX_DBL, 0.0, 1e-5, 1e-5, 0.0, 0.0, 0.0, 1e-5}
Definition at line 56 of file create_driver.h.
Definition at line 55 of file create_driver.h.