Skip to content

Commit

Permalink
Add target distance ui.
Browse files Browse the repository at this point in the history
  • Loading branch information
GuraMumei committed Apr 4, 2024
1 parent 378ba48 commit 63342ce
Show file tree
Hide file tree
Showing 2 changed files with 3 additions and 5 deletions.
3 changes: 1 addition & 2 deletions rm_referee/src/referee_base.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -13,8 +13,7 @@ RefereeBase::RefereeBase(ros::NodeHandle& nh, Base& base) : base_(base), nh_(nh)
nh.subscribe<sensor_msgs::JointState>("/joint_states", 10, &RefereeBase::jointStateCallback, this);
RefereeBase::actuator_state_sub_ =
nh.subscribe<rm_msgs::ActuatorState>("/actuator_states", 10, &RefereeBase::actuatorStateCallback, this);
RefereeBase::dbus_sub_ =
nh.subscribe<rm_msgs::DbusData>(dbus_topic_, 10, &RefereeBase::dbusDataCallback, this);
RefereeBase::dbus_sub_ = nh.subscribe<rm_msgs::DbusData>(dbus_topic_, 10, &RefereeBase::dbusDataCallback, this);
RefereeBase::chassis_cmd_sub_ =
nh.subscribe<rm_msgs::ChassisCmd>("/cmd_chassis", 10, &RefereeBase::chassisCmdDataCallback, this);
RefereeBase::vel2D_cmd_sub_ =
Expand Down
5 changes: 2 additions & 3 deletions rm_referee/src/ui/time_change_ui.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -371,7 +371,7 @@ void BulletTimeChangeUi::updateConfig()

void TargetDistanceTimeChangeUi::updateTargetDistanceData(const rm_msgs::TrackData::ConstPtr& data)
{
if(data->id == 0)
if (data->id == 0)
return;
geometry_msgs::PointStamped output;
geometry_msgs::PointStamped input;
Expand All @@ -381,8 +381,7 @@ void TargetDistanceTimeChangeUi::updateTargetDistanceData(const rm_msgs::TrackDa
// tf_buffer_.transform(input, output, "base_link");
try
{
geometry_msgs::TransformStamped transform_stamped =
tf_buffer_.lookupTransform("base_link", "odom", ros::Time(0));
geometry_msgs::TransformStamped transform_stamped = tf_buffer_.lookupTransform("base_link", "odom", ros::Time(0));
tf2::doTransform(input, output, transform_stamped);
}
catch (tf2::TransformException& ex)
Expand Down

0 comments on commit 63342ce

Please sign in to comment.