Class AgentLayer

Nested Relationships

Nested Types

Inheritance Relationships

Base Type

  • public costmap_2d::Layer

Derived Types

Class Documentation

class AgentLayer : public costmap_2d::Layer

Subclassed by cohan_layers::AgentVisibilityLayer, cohan_layers::StaticAgentLayer

Public Functions

inline AgentLayer()
void onInitialize() override

Initializes the agent layer.

void updateBounds(double origin_x, double origin_y, double origin_yaw, double *min_x, double *min_y, double *max_x, double *max_y) override

Updates the bounds of the costmap based on agent positions.

Parameters:
  • origin_x – Origin x-coordinate of the costmap

  • origin_y – Origin y-coordinate of the costmap

  • origin_yaw – Rotation angle of the costmap origin

  • min_x – Pointer to the minimum x-coordinate of the bounds

  • min_y – Pointer to the minimum y-coordinate of the bounds

  • max_x – Pointer to the maximum x-coordinate of the bounds

  • max_y – Pointer to the maximum y-coordinate of the bounds

virtual void updateCosts(costmap_2d::Costmap2D &master_grid, int min_i, int min_j, int max_i, int max_j) override = 0

Updates the cost values in the costmap based on agent positions.

Parameters:
  • master_grid – Reference to the master costmap grid.

  • min_i – Minimum index in the i-direction defining the region to update.

  • min_j – Minimum index in the j-direction defining the region to update.

  • max_i – Maximum index in the i-direction defining the region to update.

  • max_j – Maximum index in the j-direction defining the region to update.

virtual void updateBoundsFromAgents(double *min_x, double *min_y, double *max_x, double *max_y) = 0

Updates the bounds from agent positions.

Parameters:
  • min_x – Pointer to the minimum x-coordinate of the bounds

  • min_y – Pointer to the minimum y-coordinate of the bounds

  • max_x – Pointer to the maximum x-coordinate of the bounds

  • max_y – Pointer to the maximum y-coordinate of the bounds

Public Static Functions

static inline bool isDiscretized()

Indicates whether the layer is discretized.

Returns:

Always returns false as this layer is not discretized

Protected Functions

void agentsCB(const cohan_msgs::TrackedAgents &agents)

Callback for TrackedAgents.

Parameters:

agents – - Tracked agents data received from the topic Updates the agents_ member variable with the received data.

void statesCB(const agent_path_prediction::AgentsInfo &agents_info)

Callback for AgentsInfo to get the agent states.

Parameters:

agents_info – - Information about agents including their states Updates the states_ member variable with the received data.

bool shutdownCB(std_srvs::SetBoolRequest &req, std_srvs::SetBoolResponse &res)

Callback for shutdown service. Handles the shutdown of the agent layer.

Parameters:
  • req – Service request containing the shutdown flag

  • res – Service response indicating success or failure

Returns:

True if shutdown successful, false otherwise

Protected Attributes

ros::Subscriber agents_sub_
ros::Subscriber agents_states_sub_

ros subscribers

ros::ServiceServer stopmap_srv_

ros services

cohan_msgs::TrackedAgents agents_

agents

std::map<int, int> states_

agent_states

std::vector<AgentPoseVel> transformed_agents_

transformed agents

boost::recursive_mutex lock_
bool first_time_
bool reset_
bool shutdown_

flags

ros::Time last_time_

time checks

double last_min_x_
double last_min_y_
double last_max_x_
double last_max_y_

min and max x and y values for the costmap

double radius_
double amplitude_
double covar_
double cutoff_

parameters for the gaussian

double robot_radius_
double agent_radius_

radii for the agents

std::string ns_
std::string tracked_agents_sub_topic_
std::string agents_states_sub_topic_

ROS namespace and topic names.

Protected Static Functions

static inline double Guassian1D(double x, double x0, double A, double varx)

Computes a 1D Gaussian value.

Parameters:
  • x – Input value

  • x0 – Mean of the Gaussian

  • A – Amplitude of the Gaussian

  • varx – Variance of the Gaussian

Returns:

1D Gaussian value for the given input

static inline double Gaussian2D(double x, double y, double x0, double y0, double A, double varx, double vary)

Computes a 2D Gaussian value.

Parameters:
  • x – Input x-coordinate

  • y – Input y-coordinate

  • x0 – Mean x-coordinate of the Gaussian

  • y0 – Mean y-coordinate of the Gaussian

  • A – Amplitude of the Gaussian

  • varx – Variance in the x-direction

  • vary – Variance in the y-direction

Returns:

2D Gaussian value for the given inputs

static inline double Gaussian2D_skewed(double x, double y, double x0, double y0, double A, double varx, double vary, double skew_ang)

Computes a skewed 2D Gaussian value.

Parameters:
  • x – Input x-coordinate

  • y – Input y-coordinate

  • x0 – Mean x-coordinate of the Gaussian

  • y0 – Mean y-coordinate of the Gaussian

  • A – Amplitude of the Gaussian

  • varx – Variance in the x-direction

  • vary – Variance in the y-direction

  • skew_ang – Skew angle for the Gaussian

Returns:

Skewed 2D Gaussian value for the given inputs

struct AgentPoseVel

Public Members

int track_id

Unique identifier for the agent.

int type

Type of the agent (e.g., human, robot)

int state

State of the agent.

std_msgs::Header header
geometry_msgs::Pose pose
geometry_msgs::Twist velocity