4 #ifndef SR_MVSIM_NODE_CORE_H 5 #define SR_MVSIM_NODE_CORE_H 10 #include <rosgraph_msgs/Clock.h> 13 #include <dynamic_reconfigure/server.h> 17 #include <visualization_msgs/MarkerArray.h> 21 #include <mvsim/mvsimNodeConfig.h> 26 #if MRPT_VERSION >= 0x130 27 #include <mrpt/obs/CObservation.h> 30 #include <mrpt/slam/CObservation.h> 31 using mrpt::slam::CObservation;
97 std::map<std::string, ros::Publisher>
104 std::vector<TPubSubPerVehicle>
171 const std::string& frame_id,
const std::string& child_frame_id,
190 #endif // SR_MVSIM_NODE_CORE_H ros::Publisher pub_ground_truth
Publisher of "base_pose_ground_truth" topic.
static void thread_update_GUI(TThreadParams &thread_params)
std::string vehVarName(const std::string &sVarName, const mvsim::VehicleBase *veh) const
mrpt::system::CTicTac m_tim_publish_tf
TF transforms & /*/odom topics (In ms)
double m_period_ms_teleop_refresh
ros::Subscriber sub_cmd_vel
Subscribers for each vehicle's "cmd_vel" topic.
double m_transform_tolerance
mrpt::system::CTicTac realtime_tictac_
ros::Time m_base_last_cmd
Last time we received a vel_cmd (for watchdog)
ros::Publisher m_pub_map_ros
MVSimVisitor_notifyROSWorldIsUpdated(MVSimNode &parent)
virtual void onNewObservation(const mvsim::VehicleBase &veh, const CObservation *obs)
rosgraph_msgs::Clock m_clockMsg
mvsim::World::TGUIKeyEvent m_gui_key_events
"focused" vehicle)
std::function< void(VehicleBase &)> vehicle_visitor_t
mrpt::system::CTicTac m_tim_teleop_refresh
ros::Duration m_base_watchdog_timeout
const tf::Transform m_tfIdentity
Unit transform (const, created only once)
void onROSMsgCmdVel(const geometry_msgs::Twist::ConstPtr &cmd, mvsim::VehicleBase *veh)
tf::TransformBroadcaster m_tf_br
Use to send data to TF.
void loadWorldModel(const std::string &world_xml_file)
void spin()
Process pending msgs, run real-time simulation, etc.
void configCallback(mvsim::mvsimNodeConfig &config, uint32_t level)
int gui_refresh_period_ms_
Default:25.
tf2_ros::StaticTransformBroadcaster m_static_tf_br
For sending STATIC tf.
double m_period_ms_publish_tf
loadWorldModel()
ros::Publisher pub_chassis_shape
"<VEH>/chassis_shape"
std::function< void(WorldElementBase &)> world_element_visitor_t
ros::NodeHandle & m_n
published TFs
void sendStaticTF(const std::string &frame_id, const std::string &child_frame_id, const tf::Transform &tx, const ros::Time &stamp)
ros::Publisher pub_chassis_markers
"<VEH>/chassis_markers"
TThreadParams thread_params_
TCLAP::CmdLine cmd("mvsim", ' ',"version", false)
ros::Publisher pub_particlecloud
Publishers for "fake_localization" topics.
ros::Publisher pub_odom
Publisher of "odom" topic.
void initPubSubs(TPubSubPerVehicle &out_pubsubs, mvsim::VehicleBase *veh)
ros::Publisher m_pub_clock
std::vector< TPubSubPerVehicle > m_pubsub_vehicles
MVSimNode(ros::NodeHandle &n)
std::map< std::string, ros::Publisher > pub_sensors
Map <sensor_label> => publisher.
void notifyROSWorldIsUpdated()
bool m_show_gui
Default= true.
ros::Time m_sim_time
Current simulation time.
bool m_do_fake_localization
visualization_msgs::MarkerArray chassis_shape_msg
double realtime_factor_
everything: vehicles, obstacles, etc.)
ros::Publisher m_pub_map_metadata
used for simul_map publication