Skip to content

Commit

Permalink
Remove deprecations: tock (#648)
Browse files Browse the repository at this point in the history
* Remove deprecations: tock

Signed-off-by: Carlos Agüero <[email protected]>
  • Loading branch information
caguero authored Dec 4, 2024
1 parent fd0b6a1 commit 42f810f
Show file tree
Hide file tree
Showing 8 changed files with 22 additions and 107 deletions.
4 changes: 0 additions & 4 deletions CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -100,10 +100,6 @@ set(GZ_GUI_PLUGIN_RELATIVE_INSTALL_DIR
${GZ_LIB_INSTALL_DIR}/gz-${GZ_DESIGNATION}-${PROJECT_VERSION_MAJOR}/plugins
)

set(GZ_GUI_PLUGIN_INSTALL_DIR
${CMAKE_INSTALL_PREFIX}/${GZ_GUI_PLUGIN_RELATIVE_INSTALL_DIR}
)

#============================================================================
# Configure the build
#============================================================================
Expand Down
9 changes: 9 additions & 0 deletions Migration.md
Original file line number Diff line number Diff line change
Expand Up @@ -5,6 +5,15 @@ Deprecated code produces compile-time warnings. These warning serve as
notification to users that their code should be upgraded. The next major
release will remove the deprecated code.

## Gazebo GUI 9.X to 10.X

* The environment variable `GZ_GUI_PLUGIN_INSTALL_DIR` is removed. Use
`gz::gui::getPluginInstallDir()` instead.

* The camera tracking `/gui/follow` and `/gui/follow/offset` services are
removed. You can now publish a regular message on the `/gui/track` topic
passing a `gz::msgs::CameraTrack` message.

## Gazebo GUI 6.X to 7.X

* The environment variable `IGN_GUI_PLUGIN_PATH` is deprecated. Use `GZ_GUI_PLUGIN_PATH` instead.
Expand Down
12 changes: 0 additions & 12 deletions examples/standalone/scene_provider/README.md
Original file line number Diff line number Diff line change
Expand Up @@ -75,15 +75,3 @@ Update follow offset from track topic:
```bash
gz topic -t /gui/track -m gz.msgs.CameraTrack -p 'track_mode: 2, follow_target: {name: "box_model"}, follow_offset: {x: -1, y: 0, z: 1}'
```

Follow box from service (deprecated):

```bash
gz service -s /gui/follow --reqtype gz.msgs.StringMsg --reptype gz.msgs.Boolean --timeout 2000 --req 'data: "box_model"'
```

Update follow offset from follow offset service (deprecated):

```bash
gz service -s /gui/follow/offset --reqtype gz.msgs.Vector3d --reptype gz.msgs.Boolean --timeout 2000 --req 'x: 5, y: 5, z: 5'
```
2 changes: 0 additions & 2 deletions include/gz/gui/config.hh.in
Original file line number Diff line number Diff line change
Expand Up @@ -31,6 +31,4 @@

#define GZ_GUI_VERSION_HEADER "Gazebo GUI, version ${PROJECT_VERSION_FULL}\nCopyright (C) 2017 Open Source Robotics Foundation.\nReleased under the Apache 2.0 License.\n\n"

#define GZ_GUI_PLUGIN_INSTALL_DIR _Pragma ("GCC warning \"'GZ_GUI_PLUGIN_INSTALL_DIR' macro is deprecated, use gz::gui::getPluginInstallDir() function instead. \"") "${GZ_GUI_PLUGIN_INSTALL_DIR}"

#endif // GZ_GUI_CONFIG_HH_
64 changes: 0 additions & 64 deletions src/plugins/camera_tracking/CameraTracking.cc
Original file line number Diff line number Diff line change
Expand Up @@ -69,27 +69,13 @@ class CameraTracking::Implementation
/// \param[in] _msg Message is of type CameraTrack.
public: void OnTrackSub(const msgs::CameraTrack &_msg);

/// \brief Callback for a follow request
/// \param[in] _msg Request message to set the target to follow.
/// \param[in] _res Response data
/// \return True if the request is received
public: bool OnFollow(const msgs::StringMsg &_msg,
msgs::Boolean &_res);

/// \brief Callback for a move to pose request.
/// \param[in] _msg GUICamera request message.
/// \param[in] _res Response data
/// \return True if the request is received
public: bool OnMoveToPose(const msgs::GUICamera &_msg,
msgs::Boolean &_res);

/// \brief Callback for a follow offset request
/// \param[in] _msg Request message to set the camera's follow offset.
/// \param[in] _res Response data
/// \return True if the request is received
public: bool OnFollowOffset(const msgs::Vector3d &_msg,
msgs::Boolean &_res);

/// \brief Callback when a move to animation is complete
private: void OnMoveToComplete();

Expand Down Expand Up @@ -161,12 +147,6 @@ class CameraTracking::Implementation
/// \brief Move to service
public: std::string moveToService;

/// \brief Follow service (deprecated)
public: std::string followService;

/// \brief Follow offset service (deprecated)
public: std::string followOffsetService;

/// \brief The pose set from the move to pose service.
public: std::optional<math::Pose3d> moveToPoseValue;

Expand Down Expand Up @@ -224,13 +204,6 @@ void CameraTracking::Implementation::Initialize()
gzmsg << "Move to service on ["
<< this->moveToService << "]" << std::endl;

// follow
this->followService = "/gui/follow";
this->node.Advertise(this->followService,
&Implementation::OnFollow, this);
gzmsg << "Follow service on ["
<< this->followService << "] (deprecated)" << std::endl;

// track
this->trackTopic = "/gui/track";
this->node.Subscribe(this->trackTopic,
Expand Down Expand Up @@ -259,13 +232,6 @@ void CameraTracking::Implementation::Initialize()
this->node.Advertise<msgs::Pose>(this->cameraPoseTopic);
gzmsg << "Camera pose topic advertised on ["
<< this->cameraPoseTopic << "]" << std::endl;

// follow offset
this->followOffsetService = "/gui/follow/offset";
this->node.Advertise(this->followOffsetService,
&Implementation::OnFollowOffset, this);
gzmsg << "Follow offset service on ["
<< this->followOffsetService << "] (deprecated)" << std::endl;
}

/////////////////////////////////////////////////
Expand All @@ -279,21 +245,6 @@ bool CameraTracking::Implementation::OnMoveTo(const msgs::StringMsg &_msg,
return true;
}

/////////////////////////////////////////////////
bool CameraTracking::Implementation::OnFollow(const msgs::StringMsg &_msg,
msgs::Boolean &_res)
{
std::lock_guard<std::mutex> lock(this->mutex);
this->selectedFollowTarget = _msg.data();

_res.set_data(true);

this->trackMode = gz::msgs::CameraTrack::FOLLOW;

this->newTrack = true;
return true;
}

/////////////////////////////////////////////////
void CameraTracking::Implementation::OnTrackSub(const msgs::CameraTrack &_msg)
{
Expand Down Expand Up @@ -351,21 +302,6 @@ void CameraTracking::Implementation::OnMoveToPoseComplete()
this->moveToPoseDuration.reset();
}

/////////////////////////////////////////////////
bool CameraTracking::Implementation::OnFollowOffset(const msgs::Vector3d &_msg,
msgs::Boolean &_res)
{
std::lock_guard<std::mutex> lock(this->mutex);
if (!this->selectedFollowTarget.empty())
{
this->newTrack = true;
this->followOffset = msgs::Convert(_msg);
}

_res.set_data(true);
return true;
}

/////////////////////////////////////////////////
bool CameraTracking::Implementation::OnMoveToPose(const msgs::GUICamera &_msg,
msgs::Boolean &_res)
Expand Down
5 changes: 1 addition & 4 deletions src/plugins/camera_tracking/CameraTracking.hh
Original file line number Diff line number Diff line change
Expand Up @@ -27,12 +27,9 @@
namespace gz::gui::plugins
{
/// \brief This plugin provides camera tracking capabilities such as "move to"
/// and "follow".
/// and "track".
///
/// Services:
/// * `/gui/follow`: Set the user camera to follow a given target,
/// identified by name (deprecated).
/// * `/gui/follow/offset`: Set the offset for following (deprecated).
/// * `/gui/move_to`: Move the user camera to look at a given target,
/// identified by name.
/// * `/gui/move_to/pose`: Move the user camera to a given pose.
Expand Down
6 changes: 1 addition & 5 deletions src/plugins/world_control/WorldControl.cc
Original file line number Diff line number Diff line change
Expand Up @@ -245,11 +245,7 @@ void WorldControl::ProcessMsg()
{
std::lock_guard<std::recursive_mutex> lock(this->dataPtr->mutex);

// ignore the message if it's associated with a step
const auto &header = this->dataPtr->msg.header();
if (this->dataPtr->msg.stepping() ||
// (deprecated) Remove this check in Gazebo H
((header.data_size() > 0) && (header.data(0).key() == "step")))
if (this->dataPtr->msg.stepping())
{
return;
}
Expand Down
27 changes: 11 additions & 16 deletions test/integration/camera_tracking.cc
Original file line number Diff line number Diff line change
Expand Up @@ -18,6 +18,7 @@
#include <gtest/gtest.h>

#include <gz/msgs/boolean.pb.h>
#include <gz/msgs/cameratrack.pb.h>
#include <gz/msgs/pose.pb.h>
#include <gz/msgs/stringmsg.pb.h>
#include <gz/msgs/vector3d.pb.h>
Expand Down Expand Up @@ -180,22 +181,16 @@ TEST(MinimalSceneTest, GZ_UTILS_TEST_ENABLED_ONLY_ON_LINUX(Config))
trackedVis->SetWorldPose({130, 130, 130, 0, 0, 0});

// Follow
result = false;
executed = node.Request("/gui/follow", req, timeout, rep, result);
EXPECT_TRUE(executed);
EXPECT_TRUE(result);
EXPECT_TRUE(rep.data());

msgs::Vector3d reqOffset;
reqOffset.set_x(1.0);
reqOffset.set_y(1.0);
reqOffset.set_z(1.0);
result = false;
executed = node.Request("/gui/follow/offset", reqOffset, timeout, rep,
result);
EXPECT_TRUE(executed);
EXPECT_TRUE(result);
EXPECT_TRUE(rep.data());
auto trackPub = node.Advertise<gz::msgs::CameraTrack>("/gui/track");
msgs::CameraTrack trackMsg;
trackMsg.set_track_mode(msgs::CameraTrack::FOLLOW);
trackMsg.mutable_follow_target()->set_name("track_me");
trackPub.Publish(trackMsg);

trackMsg.mutable_follow_offset()->set_x(1);
trackMsg.mutable_follow_offset()->set_y(1);
trackMsg.mutable_follow_offset()->set_z(1);
trackPub.Publish(trackMsg);

// Many update loops to process many events
maxSleep = 600;
Expand Down

0 comments on commit 42f810f

Please sign in to comment.