Skip to content

Commit

Permalink
Style
Browse files Browse the repository at this point in the history
Signed-off-by: Luca Della Vedova <[email protected]>
  • Loading branch information
luca-della-vedova committed May 30, 2024
1 parent 49b2936 commit d555e77
Show file tree
Hide file tree
Showing 2 changed files with 21 additions and 14 deletions.
3 changes: 2 additions & 1 deletion rmf_robot_sim_common/src/slotcar_common.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -1025,7 +1025,8 @@ void SlotcarCommon::publish_state_topic(const rclcpp::Time& t)
robot_state_msg.path = _remaining_path;
robot_state_msg.mode = _current_mode;
// Pick the higher (most recent) one
robot_state_msg.mode.mode_request_id = std::max(pause_request.mode_request_id, _current_mode.mode_request_id);
robot_state_msg.mode.mode_request_id = std::max(pause_request.mode_request_id,
_current_mode.mode_request_id);

if (_adapter_error)
{
Expand Down
32 changes: 19 additions & 13 deletions rmf_robot_sim_gz_plugins/src/slotcar.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -52,7 +52,7 @@ class GZ_SIM_VISIBLE SlotcarPlugin
gz::transport::Node _gz_node;
rclcpp::Node::SharedPtr _ros_node;

EntityComponentManager *_ecm;
EntityComponentManager* _ecm;

Entity _entity;
Entity _joint_entity = kNullEntity;
Expand All @@ -78,8 +78,9 @@ class GZ_SIM_VISIBLE SlotcarPlugin
void init_obstacle_exclusions(EntityComponentManager& ecm);
bool get_slotcar_height(const gz::msgs::Entity& req,
gz::msgs::Double& rep);
std::pair<std::vector<Eigen::Vector3d>, std::unordered_map<Entity, Eigen::Vector3d>>
get_obstacle_positions(EntityComponentManager& ecm);
std::pair<std::vector<Eigen::Vector3d>, std::unordered_map<Entity,
Eigen::Vector3d>>
get_obstacle_positions(EntityComponentManager& ecm);

void path_request_marker_update(
const rmf_fleet_msgs::msg::PathRequest::SharedPtr);
Expand Down Expand Up @@ -119,10 +120,11 @@ bool SlotcarPlugin::attach_cart(bool attach)
if (_dispensable_positions.size() == 0)
return false;
auto min_entity = _dispensable_positions.begin()->first;
auto min_dist = (_pose.translation() - _dispensable_positions.begin()->second).norm();
auto min_dist = (_pose.translation() -
_dispensable_positions.begin()->second).norm();
for (const auto& [entity, pose] : _dispensable_positions)
{
auto dist = (_pose.translation() - pose).norm();
auto dist = (_pose.translation() - pose).norm();
if (dist < min_dist)
{
min_dist = dist;
Expand Down Expand Up @@ -157,14 +159,16 @@ bool SlotcarPlugin::attach_entity(const Entity& entity)

_joint_entity = _ecm->CreateEntity();

auto robot_link_entities = _ecm->ChildrenByComponents(_entity, components::Link());
auto robot_link_entities = _ecm->ChildrenByComponents(_entity,
components::Link());
if (robot_link_entities.size() != 1)
{
ignwarn << "Robot should only have one link, using first" << std::endl;
}
auto robot_link_entity = robot_link_entities[0];

auto cart_link_entities = _ecm->ChildrenByComponents(entity, components::Link());
auto cart_link_entities = _ecm->ChildrenByComponents(entity,
components::Link());
if (cart_link_entities.size() != 1)
{
ignwarn << "Cart should only have one link, using first" << std::endl;
Expand All @@ -174,7 +178,7 @@ bool SlotcarPlugin::attach_entity(const Entity& entity)
_ecm->CreateComponent(
_joint_entity,
components::DetachableJoint({robot_link_entity,
cart_link_entity, "fixed"}));
cart_link_entity, "fixed"}));
return true;
}

Expand Down Expand Up @@ -290,8 +294,9 @@ void SlotcarPlugin::init_obstacle_exclusions(EntityComponentManager& ecm)
_obstacle_exclusions.insert(_entity);
}

std::pair<std::vector<Eigen::Vector3d>, std::unordered_map<Entity, Eigen::Vector3d>>
SlotcarPlugin::get_obstacle_positions(EntityComponentManager& ecm)
std::pair<std::vector<Eigen::Vector3d>, std::unordered_map<Entity,
Eigen::Vector3d>>
SlotcarPlugin::get_obstacle_positions(EntityComponentManager& ecm)
{
std::vector<Eigen::Vector3d> obstacle_positions;
std::unordered_map<Entity, Eigen::Vector3d> dispensable_positions;
Expand Down Expand Up @@ -319,7 +324,7 @@ std::pair<std::vector<Eigen::Vector3d>, std::unordered_map<Entity, Eigen::Vector
if (n.find("dispensable") != std::string::npos)
{
dispensable_positions.insert({entity, rmf_plugins_utils::convert_vec(
object_position)});
object_position)});
}
return true;
});
Expand Down Expand Up @@ -497,8 +502,9 @@ void SlotcarPlugin::PreUpdate(const UpdateInfo& info,
* 1e-9;

_pose = rmf_plugins_utils::convert_pose(
ecm.Component<components::Pose>(_entity)->Data());
auto [obstacle_positions, dispensable_positions] = get_obstacle_positions(ecm);
ecm.Component<components::Pose>(_entity)->Data());
auto [obstacle_positions,
dispensable_positions] = get_obstacle_positions(ecm);
_dispensable_positions = std::move(dispensable_positions);

auto update_result = dataPtr->update(_pose, obstacle_positions, time);
Expand Down

0 comments on commit d555e77

Please sign in to comment.