Skip to content

Commit

Permalink
Merge pull request #8 from Juancams/main
Browse files Browse the repository at this point in the history
Changed package name & solved bug with dependency repos
  • Loading branch information
fmrico authored May 27, 2024
2 parents 7d09c3e + ec8a7f4 commit cee40de
Show file tree
Hide file tree
Showing 6 changed files with 45 additions and 45 deletions.
10 changes: 5 additions & 5 deletions CMakeLists.txt
Original file line number Diff line number Diff line change
@@ -1,5 +1,5 @@
cmake_minimum_required(VERSION 3.5)
project(gazebo_mocap_plugin)
project(gazebo_mocap4r2_plugin)

# Default to C++14
if(NOT CMAKE_CXX_STANDARD)
Expand All @@ -26,8 +26,8 @@ find_package(gazebo_dev REQUIRED)
find_package(gazebo_msgs REQUIRED)
find_package(gazebo_ros REQUIRED)
find_package(geometry_msgs REQUIRED)
find_package(mocap_msgs REQUIRED)
find_package(mocap_control REQUIRED)
find_package(mocap4r2_msgs REQUIRED)
find_package(mocap4r2_control REQUIRED)
find_package(rclcpp REQUIRED)

link_directories(${gazebo_dev_LIBRARY_DIRS})
Expand All @@ -53,8 +53,8 @@ ament_target_dependencies(gazebo_ros_mocap
"gazebo_dev"
"gazebo_ros"
"rclcpp"
"mocap_msgs"
"mocap_control"
"mocap4r2_msgs"
"mocap4r2_control"
"geometry_msgs"
)
ament_export_libraries(gazebo_ros_mocap)
Expand Down
6 changes: 3 additions & 3 deletions README.md
Original file line number Diff line number Diff line change
@@ -1,5 +1,5 @@

# gazebo_mocap_plugin
# gazebo_mocap4r2_plugin

This package provides you with a gazebo plugin that allows you to simulate the use of Motion Capture Markers on your simulated robot.

Expand All @@ -26,7 +26,7 @@ Add in your robot model the following, as done in [This sample model](https://gi
<visual name="mocap_sensor_visual">
<origin rpy="0 0 0" xyz=" 0 0 0"/>
<geometry>
<mesh filename="package://gazebo_mocap_plugin/meshes/rigid_body.dae" scale="0.001 0.001 0.001"/>
<mesh filename="package://gazebo_mocap4r2_plugin/meshes/rigid_body.dae" scale="0.001 0.001 0.001"/>
</geometry>
</visual>
</link>
Expand All @@ -43,7 +43,7 @@ Add in your robot model the following, as done in [This sample model](https://gi
To see it in action, just type:

```
ros2 launch gazebo_mocap_plugin tb3_simulation_launch.py
ros2 launch gazebo_mocap4r2_plugin tb3_simulation_launch.py
```

Open gzclient in other terminal:
Expand Down
12 changes: 6 additions & 6 deletions dependency_repos.repos
Original file line number Diff line number Diff line change
@@ -1,9 +1,9 @@
repositories:
mocap_msgs:
mocap4r2_msgs:
type: git
url: https://github.com/MOCAP4ROS2-Project/mocap_msgs.git
version: master
mocap:
url: https://github.com/MOCAP4ROS2-Project/mocap4r2_msgs.git
version: rolling
mocap4r2:
type: git
url: https://github.com/MOCAP4ROS2-Project/mocap.git
version: main
url: https://github.com/MOCAP4ROS2-Project/mocap4r2.git
version: rolling
2 changes: 1 addition & 1 deletion launch/tb3_simulation_launch.py
Original file line number Diff line number Diff line change
Expand Up @@ -29,7 +29,7 @@
def generate_launch_description():
# Get the launch directory
bringup_dir = get_package_share_directory('nav2_bringup')
mocap_dir = get_package_share_directory('gazebo_mocap_plugin')
mocap_dir = get_package_share_directory('gazebo_mocap4r2_plugin')
launch_dir = os.path.join(bringup_dir, 'launch')

# Create the launch configuration variables
Expand Down
6 changes: 3 additions & 3 deletions package.xml
Original file line number Diff line number Diff line change
@@ -1,7 +1,7 @@
<?xml version="1.0"?>
<?xml-model href="http://download.ros.org/schema/package_format3.xsd" schematypens="http://www.w3.org/2001/XMLSchema"?>
<package format="3">
<name>gazebo_mocap_plugin</name>
<name>gazebo_mocap4r2_plugin</name>
<version>0.0.0</version>
<description>
Gazebo plugins for mocap
Expand All @@ -17,8 +17,8 @@

<depend>rclcpp</depend>
<depend>geometry_msgs</depend>
<depend>mocap_msgs</depend>
<depend>mocap_control</depend>
<depend>mocap4r2_msgs</depend>
<depend>mocap4r2_control</depend>
<depend>gazebo_dev</depend>
<depend>gazebo_msgs</depend>
<depend>gazebo_ros</depend>
Expand Down
54 changes: 27 additions & 27 deletions src/gazebo_ros_mocap.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -23,12 +23,12 @@
#include <gazebo_plugins/gazebo_ros_mocap.hpp>
#include <gazebo_ros/node.hpp>

#include "mocap_msgs/msg/markers.hpp"
#include "mocap_msgs/msg/rigid_bodies.hpp"
#include "mocap4r2_msgs/msg/markers.hpp"
#include "mocap4r2_msgs/msg/rigid_bodies.hpp"
#include "lifecycle_msgs/msg/state.hpp"

#include "rclcpp/rclcpp.hpp"
#include "mocap_control/ControlledLifecycleNode.hpp"
#include "mocap4r2_control/ControlledLifecycleNode.hpp"

namespace gazebo
{
Expand All @@ -39,7 +39,7 @@ using CallbackReturnT =
rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn;

/// Class to hold private data members (PIMPL pattern)
class GazeboRosMocapPrivate : public mocap_control::ControlledLifecycleNode
class GazeboRosMocapPrivate : public mocap4r2_control::ControlledLifecycleNode
{
public:
GazeboRosMocapPrivate();
Expand All @@ -48,8 +48,8 @@ class GazeboRosMocapPrivate : public mocap_control::ControlledLifecycleNode
CallbackReturnT on_activate(const rclcpp_lifecycle::State & state) override;
CallbackReturnT on_deactivate(const rclcpp_lifecycle::State & state) override;

void control_start(const mocap_control_msgs::msg::Control::SharedPtr msg) override;
void control_stop(const mocap_control_msgs::msg::Control::SharedPtr msg) override;
void control_start(const mocap4r2_control_msgs::msg::Control::SharedPtr msg) override;
void control_stop(const mocap4r2_control_msgs::msg::Control::SharedPtr msg) override;

/// Connection to world update event. Callback is called while this is alive.
gazebo::event::ConnectionPtr update_connection_;
Expand All @@ -58,8 +58,8 @@ class GazeboRosMocapPrivate : public mocap_control::ControlledLifecycleNode
std::string link_name_;

/// ROS communication.
rclcpp_lifecycle::LifecyclePublisher<mocap_msgs::msg::Markers>::SharedPtr mocap_markers_pub_;
rclcpp_lifecycle::LifecyclePublisher<mocap_msgs::msg::RigidBodies>::SharedPtr
rclcpp_lifecycle::LifecyclePublisher<mocap4r2_msgs::msg::Markers>::SharedPtr mocap_markers_pub_;
rclcpp_lifecycle::LifecyclePublisher<mocap4r2_msgs::msg::RigidBodies>::SharedPtr
mocap_rigid_body_pub_;
int frame_number_{0};
};
Expand All @@ -74,9 +74,9 @@ GazeboRosMocapPrivate::GazeboRosMocapPrivate()
CallbackReturnT
GazeboRosMocapPrivate::on_configure(const rclcpp_lifecycle::State & state)
{
mocap_markers_pub_ = create_publisher<mocap_msgs::msg::Markers>(
mocap_markers_pub_ = create_publisher<mocap4r2_msgs::msg::Markers>(
"markers", rclcpp::QoS(1000));
mocap_rigid_body_pub_ = create_publisher<mocap_msgs::msg::RigidBodies>(
mocap_rigid_body_pub_ = create_publisher<mocap4r2_msgs::msg::RigidBodies>(
"rigid_bodies", rclcpp::QoS(1000));

return ControlledLifecycleNode::on_configure(state);
Expand Down Expand Up @@ -105,13 +105,13 @@ GazeboRosMocapPrivate::on_deactivate(const rclcpp_lifecycle::State & state)
}

void
GazeboRosMocapPrivate::control_start(const mocap_control_msgs::msg::Control::SharedPtr msg)
GazeboRosMocapPrivate::control_start(const mocap4r2_control_msgs::msg::Control::SharedPtr msg)
{
RCLCPP_INFO(get_logger(), "Starting mocap gazebo");
}

void
GazeboRosMocapPrivate::control_stop(const mocap_control_msgs::msg::Control::SharedPtr msg)
GazeboRosMocapPrivate::control_stop(const mocap4r2_control_msgs::msg::Control::SharedPtr msg)
{
RCLCPP_INFO(get_logger(), "Stopping mocap gazebo");
}
Expand Down Expand Up @@ -201,28 +201,28 @@ void GazeboRosMocap::OnUpdate()
auto & rot = pose.Rot();

if (impl_->mocap_markers_pub_->get_subscription_count() > 0) {
mocap_msgs::msg::Marker m1;
m1.id_type = mocap_msgs::msg::Marker::USE_INDEX;
mocap4r2_msgs::msg::Marker m1;
m1.id_type = mocap4r2_msgs::msg::Marker::USE_INDEX;
m1.marker_index = 1;
m1.translation.x = pos.X();
m1.translation.y = pos.Y();
m1.translation.z = pos.Z() + 0.05;

mocap_msgs::msg::Marker m2;
m2.id_type = mocap_msgs::msg::Marker::USE_INDEX;
mocap4r2_msgs::msg::Marker m2;
m2.id_type = mocap4r2_msgs::msg::Marker::USE_INDEX;
m2.marker_index = 2;
m2.translation.x = pos.X() + 0.02;
m2.translation.y = pos.Y();
m2.translation.z = pos.Z() + 0.03;

mocap_msgs::msg::Marker m3;
m3.id_type = mocap_msgs::msg::Marker::USE_INDEX;
mocap4r2_msgs::msg::Marker m3;
m3.id_type = mocap4r2_msgs::msg::Marker::USE_INDEX;
m3.marker_index = 3;
m3.translation.x = pos.X();
m3.translation.y = pos.Y() + 0.015;
m3.translation.z = pos.Z() + 0.03;

mocap_msgs::msg::Markers ms;
mocap4r2_msgs::msg::Markers ms;
ms.header.stamp = impl_->now();
ms.header.frame_id = "map";
ms.frame_number = impl_->frame_number_++;
Expand All @@ -232,7 +232,7 @@ void GazeboRosMocap::OnUpdate()
}

if (impl_->mocap_rigid_body_pub_->get_subscription_count() > 0) {
mocap_msgs::msg::RigidBody rb1;
mocap4r2_msgs::msg::RigidBody rb1;
rb1.rigid_body_name = "rigid_body_1";
rb1.pose.position.x = pos.X();
rb1.pose.position.y = pos.Y();
Expand All @@ -242,30 +242,30 @@ void GazeboRosMocap::OnUpdate()
rb1.pose.orientation.z = rot.Z();
rb1.pose.orientation.w = rot.W();

mocap_msgs::msg::Marker m1;
m1.id_type = mocap_msgs::msg::Marker::USE_INDEX;
mocap4r2_msgs::msg::Marker m1;
m1.id_type = mocap4r2_msgs::msg::Marker::USE_INDEX;
m1.marker_index = 1;
m1.translation.x = pos.X();
m1.translation.y = pos.Y();
m1.translation.z = pos.Z() + 0.05;

mocap_msgs::msg::Marker m2;
m2.id_type = mocap_msgs::msg::Marker::USE_INDEX;
mocap4r2_msgs::msg::Marker m2;
m2.id_type = mocap4r2_msgs::msg::Marker::USE_INDEX;
m2.marker_index = 2;
m2.translation.x = pos.X() + 0.02;
m2.translation.y = pos.Y();
m2.translation.z = pos.Z() + 0.03;

mocap_msgs::msg::Marker m3;
m3.id_type = mocap_msgs::msg::Marker::USE_INDEX;
mocap4r2_msgs::msg::Marker m3;
m3.id_type = mocap4r2_msgs::msg::Marker::USE_INDEX;
m3.marker_index = 3;
m3.translation.x = pos.X();
m3.translation.y = pos.Y() + 0.015;
m3.translation.z = pos.Z() + 0.03;

rb1.markers = {m1, m2, m3};

mocap_msgs::msg::RigidBodies rbs;
mocap4r2_msgs::msg::RigidBodies rbs;
rbs.header.stamp = impl_->now();
rbs.header.frame_id = "map";
rbs.frame_number = impl_->frame_number_++;
Expand Down

0 comments on commit cee40de

Please sign in to comment.