Class CrowdSimInterface

Nested Relationships

Nested Types

Class Documentation

class CrowdSimInterface

Public Types

enum class AnimState

Values:

enumerator WALK
enumerator IDLE
using ObjectPtr = std::shared_ptr<Object>

Public Functions

inline CrowdSimInterface()
rclcpp::Logger logger() const
void init_ros_node(const rclcpp::Node::SharedPtr node)
bool init_crowd_sim()
double get_sim_time_step() const
size_t get_num_objects() const
ObjectPtr get_object_by_id(size_t id) const
void one_step_sim(double time_step) const
double get_switch_anim_distance_th() const
std::vector<std::string> get_switch_anim_name() const
bool enabled() const
template<typename SdfPtrT>
bool read_sdf(SdfPtrT &sdf)
template<typename IgnMathPose3d>
void update_external_agent(size_t id, const IgnMathPose3d &model_pose)
template<typename IgnMathPose3d>
void update_external_agent(const AgentPtr agent_ptr, const IgnMathPose3d &model_pose)
template<typename IgnMathPose3d>
IgnMathPose3d get_agent_pose(size_t id, double delta_sim_time)
template<typename IgnMathPose3d>
IgnMathPose3d get_agent_pose(const AgentPtr agent_ptr, double delta_sim_time)

Public Members

std::shared_ptr<ModelTypeDatabase> _model_type_db_ptr
struct Object

Public Functions

AnimState get_next_state(bool condition)

Public Members

AgentPtr agent_ptr
std::string model_name
std::string type_name
bool is_external = false
AnimState current_state