#include <mvsim_node_core.h>
Classes | |
struct | MVSimVisitor_notifyROSWorldIsUpdated |
class | MyWorld |
struct | TPubSubPerVehicle |
struct | TThreadParams |
Public Member Functions | |
void | configCallback (mvsim::mvsimNodeConfig &config, uint32_t level) |
void | loadWorldModel (const std::string &world_xml_file) |
MVSimNode (ros::NodeHandle &n) | |
void | spin () |
Process pending msgs, run real-time simulation, etc. | |
~MVSimNode () | |
Public Attributes | |
int | gui_refresh_period_ms_ |
Default:25. | |
bool | m_do_fake_localization |
bool | m_show_gui |
Default= true. | |
double | m_transform_tolerance |
MyWorld | mvsim_world_ |
double | realtime_factor_ |
everything: vehicles, obstacles, etc.) | |
Protected Member Functions | |
void | initPubSubs (TPubSubPerVehicle &out_pubsubs, mvsim::VehicleBase *veh) |
void | notifyROSWorldIsUpdated () |
void | onROSMsgCmdVel (const geometry_msgs::Twist::ConstPtr &cmd, mvsim::VehicleBase *veh) |
void | sendStaticTF (const std::string &frame_id, const std::string &child_frame_id, const tf::Transform &tx, const ros::Time &stamp) |
void | spinNotifyROS () |
std::string | vehVarName (const std::string &sVarName, const mvsim::VehicleBase *veh) const |
Static Protected Member Functions | |
static void | thread_update_GUI (TThreadParams &thread_params) |
Protected Attributes | |
ros::Time | m_base_last_cmd |
Last time we received a vel_cmd (for watchdog) | |
ros::Duration | m_base_watchdog_timeout |
rosgraph_msgs::Clock | m_clockMsg |
mvsim::World::TGUIKeyEvent | m_gui_key_events |
"focused" vehicle) | |
ros::NodeHandle | m_localn |
std::string | m_msg2gui |
ros::NodeHandle & | m_n |
published TFs | |
double | m_period_ms_publish_tf |
loadWorldModel() | |
double | m_period_ms_teleop_refresh |
ros::Publisher | m_pub_clock |
ros::Publisher | m_pub_map_metadata |
used for simul_map publication | |
ros::Publisher | m_pub_map_ros |
std::vector< TPubSubPerVehicle > | m_pubsub_vehicles |
ros::Time | m_sim_time |
Current simulation time. | |
tf2_ros::StaticTransformBroadcaster | m_static_tf_br |
For sending STATIC tf. | |
size_t | m_teleop_idx_veh |
tf::TransformBroadcaster | m_tf_br |
Use to send data to TF. | |
const tf::Transform | m_tfIdentity |
Unit transform (const, created only once) | |
mrpt::utils::CTicTac | m_tim_publish_tf |
TF transforms & /*/odom topics (In ms) | |
mrpt::utils::CTicTac | m_tim_teleop_refresh |
mrpt::utils::CTicTac | realtime_tictac_ |
double | t_old_ |
std::thread | thGUI_ |
TThreadParams | thread_params_ |
bool | world_init_ok_ |
A class to wrap libmvsim as a ROS node
Definition at line 36 of file mvsim_node_core.h.
Constructor.
Definition at line 29 of file mvsim_node.cpp.
Destructor.
Definition at line 103 of file mvsim_node.cpp.
void MVSimNode::configCallback | ( | mvsim::mvsimNodeConfig & | config, |
uint32_t | level | ||
) |
Callback function for dynamic reconfigure server
Definition at line 113 of file mvsim_node.cpp.
void MVSimNode::initPubSubs | ( | TPubSubPerVehicle & | pubsubs, |
mvsim::VehicleBase * | veh | ||
) | [protected] |
initPubSubs(), called from notifyROSWorldIsUpdated() Initialize all pub/subs required for each vehicle, for the specific vehicle veh
Initialize all pub/subs required for each vehicle, for the specific vehicle veh
Definition at line 326 of file mvsim_node.cpp.
void MVSimNode::loadWorldModel | ( | const std::string & | world_xml_file | ) |
Definition at line 80 of file mvsim_node.cpp.
void MVSimNode::notifyROSWorldIsUpdated | ( | ) | [protected] |
Publish relevant stuff whenever a new world model is loaded (grid maps, etc.)
Definition at line 288 of file mvsim_node.cpp.
void MVSimNode::onROSMsgCmdVel | ( | const geometry_msgs::Twist::ConstPtr & | cmd, |
mvsim::VehicleBase * | veh | ||
) | [protected] |
Definition at line 454 of file mvsim_node.cpp.
void MVSimNode::sendStaticTF | ( | const std::string & | frame_id, |
const std::string & | child_frame_id, | ||
const tf::Transform & | tx, | ||
const ros::Time & | stamp | ||
) | [protected] |
Definition at line 312 of file mvsim_node.cpp.
void MVSimNode::spin | ( | ) |
Process pending msgs, run real-time simulation, etc.
Definition at line 125 of file mvsim_node.cpp.
void MVSimNode::spinNotifyROS | ( | ) | [protected] |
Publish everything to be published at each simulation iteration
Definition at line 472 of file mvsim_node.cpp.
void MVSimNode::thread_update_GUI | ( | TThreadParams & | thread_params | ) | [static, protected] |
Definition at line 231 of file mvsim_node.cpp.
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 722 of file mvsim_node.cpp.
Default:25.
Definition at line 67 of file mvsim_node_core.h.
ros::Time MVSimNode::m_base_last_cmd [protected] |
Last time we received a vel_cmd (for watchdog)
Definition at line 123 of file mvsim_node_core.h.
ros::Duration MVSimNode::m_base_watchdog_timeout [protected] |
Definition at line 124 of file mvsim_node_core.h.
rosgraph_msgs::Clock MVSimNode::m_clockMsg [protected] |
Definition at line 120 of file mvsim_node_core.h.
Default=true. Behaves as
Definition at line 69 of file mvsim_node_core.h.
"focused" vehicle)
Definition at line 152 of file mvsim_node_core.h.
ros::NodeHandle MVSimNode::m_localn [protected] |
Definition at line 78 of file mvsim_node_core.h.
std::string MVSimNode::m_msg2gui [protected] |
Definition at line 153 of file mvsim_node_core.h.
ros::NodeHandle& MVSimNode::m_n [protected] |
published TFs
Definition at line 77 of file mvsim_node_core.h.
double MVSimNode::m_period_ms_publish_tf [protected] |
Minimum period between publication of
Definition at line 141 of file mvsim_node_core.h.
double MVSimNode::m_period_ms_teleop_refresh [protected] |
Minimum period between update of
Definition at line 145 of file mvsim_node_core.h.
ros::Publisher MVSimNode::m_pub_clock [protected] |
Definition at line 83 of file mvsim_node_core.h.
ros::Publisher MVSimNode::m_pub_map_metadata [protected] |
used for simul_map publication
Definition at line 81 of file mvsim_node_core.h.
ros::Publisher MVSimNode::m_pub_map_ros [protected] |
Definition at line 81 of file mvsim_node_core.h.
std::vector<TPubSubPerVehicle> MVSimNode::m_pubsub_vehicles [protected] |
Pubs/Subs for each vehicle. Initialized by
Definition at line 105 of file mvsim_node_core.h.
Default= true.
Definition at line 68 of file mvsim_node_core.h.
ros::Time MVSimNode::m_sim_time [protected] |
Current simulation time.
Definition at line 121 of file mvsim_node_core.h.
For sending STATIC tf.
Definition at line 86 of file mvsim_node_core.h.
size_t MVSimNode::m_teleop_idx_veh [protected] |
for teleoperation from the GUI (selects the
Definition at line 150 of file mvsim_node_core.h.
tf::TransformBroadcaster MVSimNode::m_tf_br [protected] |
Use to send data to TF.
Definition at line 84 of file mvsim_node_core.h.
const tf::Transform MVSimNode::m_tfIdentity [protected] |
Unit transform (const, created only once)
Definition at line 126 of file mvsim_node_core.h.
mrpt::utils::CTicTac MVSimNode::m_tim_publish_tf [protected] |
TF transforms & /*/odom topics (In ms)
Definition at line 143 of file mvsim_node_core.h.
mrpt::utils::CTicTac MVSimNode::m_tim_teleop_refresh [protected] |
live info & read of teleop key strokes in GUI (In ms)
Definition at line 148 of file mvsim_node_core.h.
navigation/fake_localization for each vehicle without the need to launch additional nodes. (Default=0.1) Time tolerance for
Definition at line 73 of file mvsim_node_core.h.
The mvsim library simulated world (includes
Definition at line 63 of file mvsim_node_core.h.
double MVSimNode::realtime_factor_ |
everything: vehicles, obstacles, etc.)
(Defaul=1.0) >1: speed-up, <1: slow-down
Definition at line 66 of file mvsim_node_core.h.
mrpt::utils::CTicTac MVSimNode::realtime_tictac_ [protected] |
Definition at line 135 of file mvsim_node_core.h.
double MVSimNode::t_old_ [protected] |
Definition at line 137 of file mvsim_node_core.h.
std::thread MVSimNode::thGUI_ [protected] |
Definition at line 155 of file mvsim_node_core.h.
TThreadParams MVSimNode::thread_params_ [protected] |
Definition at line 134 of file mvsim_node_core.h.
bool MVSimNode::world_init_ok_ [protected] |
will be true after a success call to
Definition at line 138 of file mvsim_node_core.h.