Skip to content

Recreate vel cmd components each cycle #141

New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Open
wants to merge 5 commits into
base: main
Choose a base branch
from
Open
Changes from 1 commit
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
17 changes: 7 additions & 10 deletions rmf_robot_sim_gz_plugins/src/slotcar.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -211,9 +211,6 @@ void SlotcarPlugin::Configure(const Entity& entity,
enableComponent<components::Pose>(ecm, entity);
// Initialize Bounding Box component
enableComponent<components::AxisAlignedBox>(ecm, entity);
// Initialize Linear/AngularVelocityCmd components to drive slotcar
enableComponent<components::LinearVelocityCmd>(ecm, entity);
enableComponent<components::AngularVelocityCmd>(ecm, entity);

// Respond to requests asking for height (e.g. for dispenser to dispense object)
const std::string height_srv_name =
Expand All @@ -239,11 +236,6 @@ void SlotcarPlugin::send_control_signals(EntityComponentManager& ecm,
const double target_linear_speed_destination,
const std::optional<double>& max_linear_velocity)
{
auto lin_vel_cmd =
ecm.Component<components::LinearVelocityCmd>(_entity);
auto ang_vel_cmd =
ecm.Component<components::AngularVelocityCmd>(_entity);

// Open loop control
double v_robot = _prev_v_command;
double w_robot = _prev_w_command;
Expand All @@ -252,8 +244,13 @@ void SlotcarPlugin::send_control_signals(EntityComponentManager& ecm,
displacements, dt, target_linear_speed_now,
target_linear_speed_destination, max_linear_velocity);

lin_vel_cmd->Data()[0] = target_vels[0];
ang_vel_cmd->Data()[2] = target_vels[1];
gz::math::Vector3d lin_vel_cmd(0, 0, 0);
lin_vel_cmd[0] = target_vels[0];
gz::math::Vector3d ang_vel_cmd(0, 0, 0);
ang_vel_cmd[2] = target_vels[1];

ecm.SetComponentData<components::LinearVelocityCmd>(_entity, lin_vel_cmd);
ecm.SetComponentData<components::AngularVelocityCmd>(_entity, ang_vel_cmd);

// Update previous velocities
_prev_v_command = target_vels[0];
Expand Down