47 #include <Box2D/Box2D.h> 48 #include <flatland_plugins/update_timer.h> 49 #include <flatland_server/model_plugin.h> 50 #include <flatland_server/timekeeper.h> 51 #include <geometry_msgs/Twist.h> 52 #include <nav_msgs/Odometry.h> 53 #include <tf/transform_broadcaster.h> 55 #ifndef FLATLAND_PLUGINS_DIFFDRIVE_H 56 #define FLATLAND_PLUGINS_DIFFDRIVE_H 64 ros::Subscriber twist_sub_;
65 ros::Publisher odom_pub_;
66 ros::Publisher ground_truth_pub_;
67 ros::Publisher twist_pub_;
69 geometry_msgs::Twist twist_msg_;
70 nav_msgs::Odometry odom_msg_;
71 nav_msgs::Odometry ground_truth_msg_;
77 std::default_random_engine rng_;
78 std::array<std::normal_distribution<double>, 6> noise_gen_;
85 void OnInitialize(
const YAML::Node& config)
override;
91 void BeforePhysicsStep(
const Timekeeper& timekeeper)
override;
97 void TwistCallback(
const geometry_msgs::Twist& msg);
tf::TransformBroadcaster tf_broadcaster
For publish ROS TF.
Definition: diff_drive.h:73
Definition: dummy_model_plugin.h:59
bool enable_odom_pub_
YAML parameter to enable odom publishing.
Definition: diff_drive.h:74
Definition: diff_drive.h:62
Definition: timekeeper.h:55
Definition: model_plugin.h:64
Definition: update_timer.h:55
bool enable_twist_pub_
YAML parameter to enable twist publishing.
Definition: diff_drive.h:75