#include <mvsim_node_core.h>
|
void | initPubSubs (TPubSubPerVehicle &out_pubsubs, mvsim::VehicleBase *veh) |
|
void | internalOn (const mvsim::VehicleBase &veh, const mrpt::obs::CObservation2DRangeScan &obs) |
|
void | internalOn (const mvsim::VehicleBase &veh, const mrpt::obs::CObservationImage &obs) |
|
void | internalOn (const mvsim::VehicleBase &veh, const mrpt::obs::CObservation3DRangeScan &obs) |
|
void | internalOn (const mvsim::VehicleBase &veh, const mrpt::obs::CObservationPointCloud &obs) |
|
void | internalOn (const mvsim::VehicleBase &veh, const mrpt::obs::CObservationIMU &obs) |
|
rclcpp::Time | myNow () const |
|
void | notifyROSWorldIsUpdated () |
|
void | onROSMsgCmdVel (const geometry_msgs::msg::Twist::ConstSharedPtr &cmd, mvsim::VehicleBase *veh) |
|
void | publishVehicles (mvsim::VehicleBase &veh) |
|
void | publishWorldElements (mvsim::WorldElementBase &obj) |
|
void | sendStaticTF (const std::string &frame_id, const std::string &child_frame_id, const tf2::Transform &tx, const rclcpp::Time &stamp) |
|
void | spinNotifyROS () |
|
std::string | vehVarName (const std::string &sVarName, const mvsim::VehicleBase &veh) const |
|
A class to wrap libmvsim as a ROS node
Definition at line 61 of file mvsim_node_core.h.
◆ MVSimNode()
MVSimNode::MVSimNode |
( |
rclcpp::Node::SharedPtr & |
n | ) |
|
◆ ~MVSimNode()
MVSimNode::~MVSimNode |
( |
| ) |
|
◆ initPubSubs()
Initialize all pub/subs required for each vehicle, for the specific vehicle veh
Definition at line 566 of file mvsim_node.cpp.
◆ internalOn() [1/5]
◆ internalOn() [2/5]
◆ internalOn() [3/5]
◆ internalOn() [4/5]
◆ internalOn() [5/5]
◆ launch_mvsim_server()
void MVSimNode::launch_mvsim_server |
( |
| ) |
|
◆ loadWorldModel()
void MVSimNode::loadWorldModel |
( |
const std::string & |
world_xml_file | ) |
|
◆ myNow()
rclcpp::Time MVSimNode::myNow |
( |
| ) |
const |
|
protected |
◆ notifyROSWorldIsUpdated()
void MVSimNode::notifyROSWorldIsUpdated |
( |
| ) |
|
|
protected |
Publish relevant stuff whenever a new world model is loaded (grid maps, etc.)
Definition at line 502 of file mvsim_node.cpp.
◆ onNewObservation()
void MVSimNode::onNewObservation |
( |
const mvsim::Simulable & |
veh, |
|
|
const mrpt::obs::CObservation::Ptr & |
obs |
|
) |
| |
◆ onROSMsgCmdVel()
void MVSimNode::onROSMsgCmdVel |
( |
const geometry_msgs::msg::Twist::ConstSharedPtr & |
cmd, |
|
|
mvsim::VehicleBase * |
veh |
|
) |
| |
|
protected |
◆ publishVehicles()
◆ publishWorldElements()
◆ sendStaticTF()
void MVSimNode::sendStaticTF |
( |
const std::string & |
frame_id, |
|
|
const std::string & |
child_frame_id, |
|
|
const tf2::Transform & |
tx, |
|
|
const rclcpp::Time & |
stamp |
|
) |
| |
|
protected |
◆ spin()
Process pending msgs, run real-time simulation, etc.
Definition at line 308 of file mvsim_node.cpp.
◆ spinNotifyROS()
void MVSimNode::spinNotifyROS |
( |
| ) |
|
|
protected |
Publish everything to be published at each simulation iteration
Definition at line 792 of file mvsim_node.cpp.
◆ terminateSimulation()
void MVSimNode::terminateSimulation |
( |
| ) |
|
◆ thread_update_GUI()
◆ vehVarName()
std::string MVSimNode::vehVarName |
( |
const std::string & |
sVarName, |
|
|
const mvsim::VehicleBase & |
veh |
|
) |
| const |
|
protected |
Creates the string "/<VEH_NAME>/<VAR_NAME>" if there're more than one vehicle in the World, or "/<VAR_NAME>" otherwise.
Definition at line 1069 of file mvsim_node.cpp.
◆ base_last_cmd_
rclcpp::Time MVSimNode::base_last_cmd_ |
|
protected |
◆ base_watchdog_timeout_
rclcpp::Duration MVSimNode::base_watchdog_timeout_ = std::chrono::seconds(1) |
|
protected |
◆ clock_
rclcpp::Clock::SharedPtr MVSimNode::clock_ |
|
protected |
◆ do_fake_localization_
bool MVSimNode::do_fake_localization_ = true |
Default=true. Behaves as navigation/fake_localization for each vehicle without the need to launch additional nodes.
Definition at line 105 of file mvsim_node_core.h.
◆ gui_key_events_
◆ gui_refresh_period_ms_
int MVSimNode::gui_refresh_period_ms_ = 50 |
◆ headless_
bool MVSimNode::headless_ = false |
◆ msg2gui_
std::string MVSimNode::msg2gui_ |
|
protected |
◆ mvsim_server_
◆ mvsim_world_
Initial value:=
std::make_shared<mvsim::World>()
The mvsim library simulated world (includes everything: vehicles, obstacles, etc.)
Definition at line 92 of file mvsim_node_core.h.
◆ n_
rclcpp::Node::SharedPtr MVSimNode::n_ |
|
protected |
◆ period_ms_publish_tf_
double MVSimNode::period_ms_publish_tf_ = 20 |
|
protected |
Minimum period between publication of TF transforms & /*/odom topics (In ms)
Definition at line 239 of file mvsim_node_core.h.
◆ period_ms_teleop_refresh_
double MVSimNode::period_ms_teleop_refresh_ = 100 |
|
protected |
Minimum period between update of live info & read of teleop key strokes in GUI (In ms)
Definition at line 245 of file mvsim_node_core.h.
◆ profiler_
mrpt::system::CTimeLogger MVSimNode::profiler_ {true , "mvsim_node"} |
|
protected |
◆ pub_map_metadata_
rclcpp::Publisher<nav_msgs::msg::MapMetaData>::SharedPtr MVSimNode::pub_map_metadata_ |
|
protected |
◆ pub_map_ros_
rclcpp::Publisher<nav_msgs::msg::OccupancyGrid>::SharedPtr MVSimNode::pub_map_ros_ |
|
protected |
◆ publisher_history_len_
int MVSimNode::publisher_history_len_ = 50 |
◆ pubsub_vehicles_
◆ pubsub_vehicles_mtx_
std::mutex MVSimNode::pubsub_vehicles_mtx_ |
|
protected |
◆ realtime_factor_
double MVSimNode::realtime_factor_ = 1.0 |
◆ realtime_tictac_
mrpt::system::CTicTac MVSimNode::realtime_tictac_ |
|
protected |
◆ ros_publisher_workers_
mrpt::WorkerThreadsPool MVSimNode::ros_publisher_workers_ |
Initial value:{
4 , mrpt::WorkerThreadsPool::POLICY_FIFO}
Definition at line 95 of file mvsim_node_core.h.
◆ static_tf_br_
◆ t_old_
double MVSimNode::t_old_ = -1 |
|
protected |
◆ teleop_idx_veh_
size_t MVSimNode::teleop_idx_veh_ = 0 |
|
protected |
for teleoperation from the GUI (selects the focused" vehicle)
Definition at line 249 of file mvsim_node_core.h.
◆ tf_br_
◆ tfIdentity_
◆ thGUI_
std::thread MVSimNode::thGUI_ |
|
protected |
◆ thread_params_
◆ tim_publish_tf_
mrpt::system::CTicTac MVSimNode::tim_publish_tf_ |
|
protected |
◆ tim_teleop_refresh_
mrpt::system::CTicTac MVSimNode::tim_teleop_refresh_ |
|
protected |
◆ transform_tolerance_
double MVSimNode::transform_tolerance_ = 0.1 |
◆ ts_
rclcpp::TimeSource MVSimNode::ts_ {n_} |
|
protected |
◆ world_init_ok_
bool MVSimNode::world_init_ok_ = false |
|
protected |
The documentation for this class was generated from the following files: