diff --git a/.github/workflows/ci.yaml b/.github/workflows/ci.yaml index 69706a3e..a35bb338 100644 --- a/.github/workflows/ci.yaml +++ b/.github/workflows/ci.yaml @@ -47,11 +47,11 @@ jobs: run: | cd /home/ros2_ws/ . /opt/ros/galactic/local_setup.sh - colcon build --packages-up-to ignition_ros2_control_demos + colcon build --packages-up-to ign_ros2_control_demos - name: Run tests id: test run: | cd /home/ros2_ws/ . /opt/ros/galactic/local_setup.sh - colcon test --event-handlers console_direct+ --packages-select ignition_ros2_control ignition_ros2_control_demos + colcon test --event-handlers console_direct+ --packages-select ign_ros2_control ign_ros2_control_demos colcon test-result diff --git a/Dockerfile/Dockerfile b/Dockerfile/Dockerfile index a61fd94c..ed2bc432 100644 --- a/Dockerfile/Dockerfile +++ b/Dockerfile/Dockerfile @@ -33,4 +33,4 @@ RUN cd /home/ros2_ws/ \ COPY entrypoint.sh /entrypoint.sh ENTRYPOINT ["/entrypoint.sh"] -CMD ros2 launch ignition_ros2_control_demos cart_example_position.launch.py +CMD ros2 launch ign_ros2_control_demos cart_example_position.launch.py diff --git a/README.md b/README.md index 912a369a..e10b3ef5 100644 --- a/README.md +++ b/README.md @@ -27,7 +27,7 @@ If you want to run this with `ROS 2 Foxy` please check the branch `foxy`. ```bash cd Dockerfile -docker build -t ignition_ros2_control . +docker build -t ign_ros2_control . ``` ### To run the demo @@ -37,7 +37,7 @@ docker build -t ignition_ros2_control . Docker allows us to run the demo without the GUI if configured properly. The following command runs the demo without the GUI: ```bash -docker run -it --rm --name ignition_ros2_control_demo --net host ignition_ros2_control ros2 launch ignition_ros2_control_demos cart_example_position.launch.py gui:=false +docker run -it --rm --name ignition_ros2_control_demo --net host ign_ros2_control ros2 launch ign_ros2_control_demos cart_example_position.launch.py gui:=false ``` Then on your local machine, you can run the Gazebo client: @@ -55,7 +55,7 @@ mounting file permissions. You can install this tool with the following [instruc The following command will launch Ignition: ```bash -rocker --x11 --nvidia --name ignition_ros2_control_demo ignition_ros2_control:latest +rocker --x11 --nvidia --name ignition_ros2_control_demo ign_ros2_control:latest ``` The following commands allow the cart to be moved along the rail: @@ -63,7 +63,7 @@ The following commands allow the cart to be moved along the rail: ```bash docker exec -it ignition_ros2_control_demo bash source /home/ros2_ws/install/setup.bash -ros2 run ignition_ros2_control_demos example_position +ros2 run ign_ros2_control_demos example_position ``` ## Add ros2_control tag to a URDF @@ -78,7 +78,7 @@ include: ```xml - ignition_ros2_control/IgnitionSystem + ign_ros2_control/IgnitionSystem @@ -92,31 +92,31 @@ include: ``` -## Add the ignition_ros2_control plugin +## Add the ign_ros2_control plugin In addition to the `ros2_control` tags, a Gazebo plugin needs to be added to your URDF that actually parses the `ros2_control` tags and loads the appropriate hardware interfaces and -controller manager. By default the `ignition_ros2_control` plugin is very simple, though it is also +controller manager. By default the `ign_ros2_control` plugin is very simple, though it is also extensible via an additional plugin architecture to allow power users to create their own custom robot hardware interfaces between `ros2_control` and Gazebo. ```xml - + robot_description robot_state_publisher - $(find ignition_ros2_control_demos)/config/cartpole_controller.yaml + $(find ign_ros2_control_demos)/config/cartpole_controller.yaml ``` -The `ignition_ros2_control` `` tag also has the following optional child elements: +The `ign_ros2_control` `` tag also has the following optional child elements: - ``: YAML file with the configuration of the controllers -#### Default ignition_ros2_control Behavior +#### Default ign_ros2_control Behavior -By default, without a `` tag, `ignition_ros2_control` will attempt to get all of the information it needs to interface with a ros2_control-based controller out of the URDF. This is sufficient for most cases, and good for at least getting started. +By default, without a `` tag, `ign_ros2_control` will attempt to get all of the information it needs to interface with a ros2_control-based controller out of the URDF. This is sufficient for most cases, and good for at least getting started. The default behavior provides the following ros2_control interfaces: @@ -124,11 +124,11 @@ The default behavior provides the following ros2_control interfaces: - hardware_interface::EffortJointInterface - hardware_interface::VelocityJointInterface -#### Advanced: custom ignition_ros2_control Simulation Plugins +#### Advanced: custom ign_ros2_control Simulation Plugins -The `ignition_ros2_control` Gazebo plugin also provides a pluginlib-based interface to implement custom interfaces between Gazebo and `ros2_control` for simulating more complex mechanisms (nonlinear springs, linkages, etc). +The `ign_ros2_control` Gazebo plugin also provides a pluginlib-based interface to implement custom interfaces between Gazebo and `ros2_control` for simulating more complex mechanisms (nonlinear springs, linkages, etc). -These plugins must inherit the `ignition_ros2_control::IgnitionSystemInterface`, which implements a simulated `ros2_control` +These plugins must inherit the `ign_ros2_control::IgnitionSystemInterface`, which implements a simulated `ros2_control` `hardware_interface::SystemInterface`. SystemInterface provides API-level access to read and command joint properties. The respective IgnitionSystemInterface sub-class is specified in a URDF model and is loaded when the @@ -136,12 +136,12 @@ robot model is loaded. For example, the following XML will load the default plug ```xml - ignition_ros2_control/IgnitionSystem + ign_ros2_control/IgnitionSystem ... - + ... @@ -154,8 +154,8 @@ and use the tag `` to set the controller ma ```xml - - $(find ignition_ros2_control_demos)/config/cartpole_controller.yaml + + $(find ign_ros2_control_demos)/config/cartpole_controller.yaml controller_manager @@ -184,14 +184,14 @@ cart_pole_controller: ``` #### Executing the examples -There are some examples in the `ignition_ros2_control_demos` package. These examples allow to launch a cart in a 30 meter rail. +There are some examples in the `ign_ros2_control_demos` package. These examples allow to launch a cart in a 30 meter rail. You can run some of the example configurations by running the following commands: ```bash -ros2 launch ignition_ros2_control_demos cart_example_position.launch.py -ros2 launch ignition_ros2_control_demos cart_example_velocity.launch.py -ros2 launch ignition_ros2_control_demos cart_example_effort.launch.py +ros2 launch ign_ros2_control_demos cart_example_position.launch.py +ros2 launch ign_ros2_control_demos cart_example_velocity.launch.py +ros2 launch ign_ros2_control_demos cart_example_effort.launch.py ``` Send example commands: @@ -199,7 +199,7 @@ Send example commands: When the Gazebo world is launched, you can run some of the following commands to move the cart. ```bash -ros2 run ignition_ros2_control_demos example_position -ros2 run ignition_ros2_control_demos example_velocity -ros2 run ignition_ros2_control_demos example_effort +ros2 run ign_ros2_control_demos example_position +ros2 run ign_ros2_control_demos example_velocity +ros2 run ign_ros2_control_demos example_effort ``` diff --git a/ign_ros2_control/CHANGELOG.rst b/ign_ros2_control/CHANGELOG.rst new file mode 100644 index 00000000..b5f66632 --- /dev/null +++ b/ign_ros2_control/CHANGELOG.rst @@ -0,0 +1,11 @@ +^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +Changelog for package ign_ros2_control +^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ + +0.1.0 (2022-05-01) +------------------ +* Ignition ros2 control (`#1 `_) + Co-authored-by: ahcorde + Co-authored-by: Louise Poubel + Co-authored-by: Vatan Aksoy Tezer +* Contributors: Alejandro Hernández Cordero, Louise Poubel, Vatan Aksoy Tezer diff --git a/ignition_ros2_control/CMakeLists.txt b/ign_ros2_control/CMakeLists.txt similarity index 85% rename from ignition_ros2_control/CMakeLists.txt rename to ign_ros2_control/CMakeLists.txt index f7da0be2..342941bf 100644 --- a/ignition_ros2_control/CMakeLists.txt +++ b/ign_ros2_control/CMakeLists.txt @@ -1,5 +1,5 @@ cmake_minimum_required(VERSION 3.5) -project(ignition_ros2_control) +project(ign_ros2_control) # Default to C11 if(NOT CMAKE_C_STANDARD) @@ -52,7 +52,7 @@ set(IGN_PLUGIN_VER ${ignition-plugin1_VERSION_MAJOR}) include_directories(include) add_library(${PROJECT_NAME}-system SHARED - src/ignition_ros2_control_plugin.cpp + src/ign_ros2_control_plugin.cpp ) target_link_libraries(${PROJECT_NAME}-system @@ -72,21 +72,21 @@ ament_target_dependencies(${PROJECT_NAME}-system ######### -add_library(ignition_hardware_plugins SHARED - src/ignition_system.cpp +add_library(ign_hardware_plugins SHARED + src/ign_system.cpp ) -ament_target_dependencies(ignition_hardware_plugins +ament_target_dependencies(ign_hardware_plugins rclcpp_lifecycle hardware_interface rclcpp ) -target_link_libraries(ignition_hardware_plugins +target_link_libraries(ign_hardware_plugins ignition-gazebo${IGN_GAZEBO_VER}::core ) ## Install install(TARGETS - ignition_hardware_plugins + ign_hardware_plugins ARCHIVE DESTINATION lib LIBRARY DESTINATION lib RUNTIME DESTINATION bin @@ -99,14 +99,14 @@ if(BUILD_TESTING) endif() ament_export_include_directories(include) -ament_export_libraries(${PROJECT_NAME} ignition_hardware_plugins) +ament_export_libraries(${PROJECT_NAME} ign_hardware_plugins) # Install directories install(TARGETS ${PROJECT_NAME}-system DESTINATION lib ) -pluginlib_export_plugin_description_file(ignition_ros2_control ignition_hardware_plugins.xml) +pluginlib_export_plugin_description_file(ign_ros2_control ign_hardware_plugins.xml) # Setup the project ament_package() diff --git a/ignition_ros2_control/LICENSE b/ign_ros2_control/LICENSE similarity index 100% rename from ignition_ros2_control/LICENSE rename to ign_ros2_control/LICENSE diff --git a/ign_ros2_control/ign_hardware_plugins.xml b/ign_ros2_control/ign_hardware_plugins.xml new file mode 100644 index 00000000..3d245541 --- /dev/null +++ b/ign_ros2_control/ign_hardware_plugins.xml @@ -0,0 +1,10 @@ + + + + GazeboPositionJoint + + + diff --git a/ignition_ros2_control/include/ignition_ros2_control/ignition_ros2_control_plugin.hpp b/ign_ros2_control/include/ign_ros2_control/ign_ros2_control_plugin.hpp similarity index 86% rename from ignition_ros2_control/include/ignition_ros2_control/ignition_ros2_control_plugin.hpp rename to ign_ros2_control/include/ign_ros2_control/ign_ros2_control_plugin.hpp index 3b23bfbf..20ff52e1 100644 --- a/ignition_ros2_control/include/ignition_ros2_control/ignition_ros2_control_plugin.hpp +++ b/ign_ros2_control/include/ign_ros2_control/ign_ros2_control_plugin.hpp @@ -12,14 +12,14 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef IGNITION_ROS2_CONTROL__IGNITION_ROS2_CONTROL_PLUGIN_HPP_ -#define IGNITION_ROS2_CONTROL__IGNITION_ROS2_CONTROL_PLUGIN_HPP_ +#ifndef IGN_ROS2_CONTROL__IGN_ROS2_CONTROL_PLUGIN_HPP_ +#define IGN_ROS2_CONTROL__IGN_ROS2_CONTROL_PLUGIN_HPP_ #include #include -namespace ignition_ros2_control +namespace ign_ros2_control { // Forward declarations. class IgnitionROS2ControlPluginPrivate; @@ -57,6 +57,6 @@ class IgnitionROS2ControlPlugin /// \brief Private data pointer. std::unique_ptr dataPtr; }; -} // namespace ignition_ros2_control +} // namespace ign_ros2_control -#endif // IGNITION_ROS2_CONTROL__IGNITION_ROS2_CONTROL_PLUGIN_HPP_ +#endif // IGN_ROS2_CONTROL__IGN_ROS2_CONTROL_PLUGIN_HPP_ diff --git a/ignition_ros2_control/include/ignition_ros2_control/ignition_system.hpp b/ign_ros2_control/include/ign_ros2_control/ign_system.hpp similarity index 86% rename from ignition_ros2_control/include/ignition_ros2_control/ignition_system.hpp rename to ign_ros2_control/include/ign_ros2_control/ign_system.hpp index 417785b8..ef11f89f 100644 --- a/ignition_ros2_control/include/ignition_ros2_control/ignition_system.hpp +++ b/ign_ros2_control/include/ign_ros2_control/ign_system.hpp @@ -13,24 +13,24 @@ // limitations under the License. -#ifndef IGNITION_ROS2_CONTROL__IGNITION_SYSTEM_HPP_ -#define IGNITION_ROS2_CONTROL__IGNITION_SYSTEM_HPP_ +#ifndef IGN_ROS2_CONTROL__IGN_SYSTEM_HPP_ +#define IGN_ROS2_CONTROL__IGN_SYSTEM_HPP_ #include #include #include #include -#include "ignition_ros2_control/ignition_system_interface.hpp" +#include "ign_ros2_control/ign_system_interface.hpp" #include "rclcpp_lifecycle/state.hpp" #include "rclcpp_lifecycle/node_interfaces/lifecycle_node_interface.hpp" -namespace ignition_ros2_control +namespace ign_ros2_control { // Forward declaration class IgnitionSystemPrivate; -// These class must inherit `ignition_ros2_control::IgnitionSystemInterface` which implements a +// These class must inherit `ign_ros2_control::IgnitionSystemInterface` which implements a // simulated `ros2_control` `hardware_interface::SystemInterface`. class IgnitionSystem : public IgnitionSystemInterface @@ -78,6 +78,6 @@ class IgnitionSystem : public IgnitionSystemInterface std::unique_ptr dataPtr; }; -} // namespace ignition_ros2_control +} // namespace ign_ros2_control -#endif // IGNITION_ROS2_CONTROL__IGNITION_SYSTEM_HPP_ +#endif // IGN_ROS2_CONTROL__IGN_SYSTEM_HPP_ diff --git a/ignition_ros2_control/include/ignition_ros2_control/ignition_system_interface.hpp b/ign_ros2_control/include/ign_ros2_control/ign_system_interface.hpp similarity index 92% rename from ignition_ros2_control/include/ignition_ros2_control/ignition_system_interface.hpp rename to ign_ros2_control/include/ign_ros2_control/ign_system_interface.hpp index 3c8e4593..42b23876 100644 --- a/ignition_ros2_control/include/ignition_ros2_control/ignition_system_interface.hpp +++ b/ign_ros2_control/include/ign_ros2_control/ign_system_interface.hpp @@ -13,8 +13,8 @@ // limitations under the License. -#ifndef IGNITION_ROS2_CONTROL__IGNITION_SYSTEM_INTERFACE_HPP_ -#define IGNITION_ROS2_CONTROL__IGNITION_SYSTEM_INTERFACE_HPP_ +#ifndef IGN_ROS2_CONTROL__IGN_SYSTEM_INTERFACE_HPP_ +#define IGN_ROS2_CONTROL__IGN_SYSTEM_INTERFACE_HPP_ #include @@ -28,7 +28,7 @@ #include #include -namespace ignition_ros2_control +namespace ign_ros2_control { /// \brief This class allows us to handle flags easily, instead of using strings @@ -102,6 +102,6 @@ class IgnitionSystemInterface rclcpp::Node::SharedPtr nh_; }; -} // namespace ignition_ros2_control +} // namespace ign_ros2_control -#endif // IGNITION_ROS2_CONTROL__IGNITION_SYSTEM_INTERFACE_HPP_ +#endif // IGN_ROS2_CONTROL__IGN_SYSTEM_INTERFACE_HPP_ diff --git a/ignition_ros2_control/package.xml b/ign_ros2_control/package.xml similarity index 90% rename from ignition_ros2_control/package.xml rename to ign_ros2_control/package.xml index 6956c88e..42d07a56 100644 --- a/ignition_ros2_control/package.xml +++ b/ign_ros2_control/package.xml @@ -1,6 +1,6 @@ - ignition_ros2_control + ign_ros2_control 0.0.0 Ignition ros2_control package allows to control simulated robots using ros2_control framework. Alejandro Hernández @@ -28,6 +28,6 @@ ament_cmake - + diff --git a/ignition_ros2_control/src/ignition_ros2_control_plugin.cpp b/ign_ros2_control/src/ign_ros2_control_plugin.cpp similarity index 92% rename from ignition_ros2_control/src/ignition_ros2_control_plugin.cpp rename to ign_ros2_control/src/ign_ros2_control_plugin.cpp index 00cb272d..3ec590a9 100644 --- a/ignition_ros2_control/src/ignition_ros2_control_plugin.cpp +++ b/ign_ros2_control/src/ign_ros2_control_plugin.cpp @@ -37,10 +37,10 @@ #include #include -#include "ignition_ros2_control/ignition_ros2_control_plugin.hpp" -#include "ignition_ros2_control/ignition_system.hpp" +#include "ign_ros2_control/ign_ros2_control_plugin.hpp" +#include "ign_ros2_control/ign_system.hpp" -namespace ignition_ros2_control +namespace ign_ros2_control { ////////////////////////////////////////////////// class IgnitionROS2ControlPluginPrivate @@ -80,7 +80,7 @@ class IgnitionROS2ControlPluginPrivate /// \brief Interface loader std::shared_ptr> + ign_ros2_control::IgnitionSystemInterface>> robot_hw_sim_loader_{nullptr}; /// \brief Controller manager @@ -137,7 +137,7 @@ IgnitionROS2ControlPluginPrivate::GetEnabledJoints( { RCLCPP_INFO( node_->get_logger(), - "[ignition_ros2_control] Fixed joint [%s] (Entity=%lu)] is skipped", + "[ign_ros2_control] Fixed joint [%s] (Entity=%lu)] is skipped", jointName.c_str(), jointEntity); continue; } @@ -148,7 +148,7 @@ IgnitionROS2ControlPluginPrivate::GetEnabledJoints( { RCLCPP_WARN( node_->get_logger(), - "[ignition_ros2_control] Joint [%s] (Entity=%lu)] is of unsupported type." + "[ign_ros2_control] Joint [%s] (Entity=%lu)] is of unsupported type." " Only joints with a single axis are supported.", jointName.c_str(), jointEntity); continue; @@ -157,7 +157,7 @@ IgnitionROS2ControlPluginPrivate::GetEnabledJoints( { RCLCPP_WARN( node_->get_logger(), - "[ignition_ros2_control] Joint [%s] (Entity=%lu)] is of unknown type", + "[ign_ros2_control] Joint [%s] (Entity=%lu)] is of unknown type", jointName.c_str(), jointEntity); continue; } @@ -212,7 +212,7 @@ std::string IgnitionROS2ControlPluginPrivate::getURDF() const break; } else { RCLCPP_ERROR( - node_->get_logger(), "ignition_ros2_control plugin is waiting for model" + node_->get_logger(), "ign_ros2_control plugin is waiting for model" " URDF in parameter [%s] on the ROS param server.", this->robot_description_.c_str()); } @@ -359,7 +359,7 @@ void IgnitionROS2ControlPlugin::Configure( } catch (const std::runtime_error & ex) { RCLCPP_ERROR_STREAM( this->dataPtr->node_->get_logger(), - "Error parsing URDF in ignition_ros2_control plugin, plugin not active : " << ex.what()); + "Error parsing URDF in ign_ros2_control plugin, plugin not active : " << ex.what()); return; } @@ -368,9 +368,9 @@ void IgnitionROS2ControlPlugin::Configure( try { this->dataPtr->robot_hw_sim_loader_.reset( - new pluginlib::ClassLoader( - "ignition_ros2_control", - "ignition_ros2_control::IgnitionSystemInterface")); + new pluginlib::ClassLoader( + "ign_ros2_control", + "ign_ros2_control::IgnitionSystemInterface")); } catch (pluginlib::LibraryLoadException & ex) { RCLCPP_ERROR( this->dataPtr->node_->get_logger(), "Failed to create robot simulation interface loader: %s ", @@ -380,7 +380,7 @@ void IgnitionROS2ControlPlugin::Configure( for (unsigned int i = 0; i < control_hardware.size(); ++i) { std::string robot_hw_sim_type_str_ = control_hardware[i].hardware_class_type; - auto ignitionSystem = std::unique_ptr( + auto ignitionSystem = std::unique_ptr( this->dataPtr->robot_hw_sim_loader_->createUnmanagedInstance(robot_hw_sim_type_str_)); if (!ignitionSystem->initSim( @@ -464,17 +464,17 @@ void IgnitionROS2ControlPlugin::PostUpdate( if (sim_period >= this->dataPtr->control_period_) { this->dataPtr->last_update_sim_time_ros_ = sim_time_ros; auto ign_controller_manager = - std::dynamic_pointer_cast( + std::dynamic_pointer_cast( this->dataPtr->controller_manager_); this->dataPtr->controller_manager_->read(); this->dataPtr->controller_manager_->update(sim_time_ros, sim_period); } } -} // namespace ignition_ros2_control +} // namespace ign_ros2_control IGNITION_ADD_PLUGIN( - ignition_ros2_control::IgnitionROS2ControlPlugin, + ign_ros2_control::IgnitionROS2ControlPlugin, ignition::gazebo::System, - ignition_ros2_control::IgnitionROS2ControlPlugin::ISystemConfigure, - ignition_ros2_control::IgnitionROS2ControlPlugin::ISystemPreUpdate, - ignition_ros2_control::IgnitionROS2ControlPlugin::ISystemPostUpdate) + ign_ros2_control::IgnitionROS2ControlPlugin::ISystemConfigure, + ign_ros2_control::IgnitionROS2ControlPlugin::ISystemPreUpdate, + ign_ros2_control::IgnitionROS2ControlPlugin::ISystemPostUpdate) diff --git a/ignition_ros2_control/src/ignition_system.cpp b/ign_ros2_control/src/ign_system.cpp similarity index 97% rename from ignition_ros2_control/src/ignition_system.cpp rename to ign_ros2_control/src/ign_system.cpp index 0477a19b..db76c652 100644 --- a/ignition_ros2_control/src/ignition_system.cpp +++ b/ign_ros2_control/src/ign_system.cpp @@ -12,7 +12,7 @@ // See the License for the specific language governing permissions and // limitations under the License. -#include "ignition_ros2_control/ignition_system.hpp" +#include "ign_ros2_control/ign_system.hpp" #include @@ -65,7 +65,7 @@ struct jointData ignition::gazebo::Entity sim_joint; /// \brief Control method defined in the URDF for each joint. - ignition_ros2_control::IgnitionSystemInterface::ControlMethod joint_control_method; + ign_ros2_control::IgnitionSystemInterface::ControlMethod joint_control_method; }; class ImuData @@ -101,7 +101,7 @@ void ImuData::OnIMU(const ignition::msgs::IMU & _msg) this->imu_sensor_data_[9] = _msg.linear_acceleration().z(); } -class ignition_ros2_control::IgnitionSystemPrivate +class ign_ros2_control::IgnitionSystemPrivate { public: IgnitionSystemPrivate() = default; @@ -133,7 +133,7 @@ class ignition_ros2_control::IgnitionSystemPrivate ignition::transport::Node node; }; -namespace ignition_ros2_control +namespace ign_ros2_control { bool IgnitionSystem::initSim( @@ -460,8 +460,8 @@ hardware_interface::return_type IgnitionSystem::write() return hardware_interface::return_type::OK; } -} // namespace ignition_ros2_control +} // namespace ign_ros2_control #include "pluginlib/class_list_macros.hpp" // NOLINT PLUGINLIB_EXPORT_CLASS( - ignition_ros2_control::IgnitionSystem, ignition_ros2_control::IgnitionSystemInterface) + ign_ros2_control::IgnitionSystem, ign_ros2_control::IgnitionSystemInterface) diff --git a/ign_ros2_control_demos/CHANGELOG.rst b/ign_ros2_control_demos/CHANGELOG.rst new file mode 100644 index 00000000..fbccccd4 --- /dev/null +++ b/ign_ros2_control_demos/CHANGELOG.rst @@ -0,0 +1,11 @@ +^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +Changelog for package ign_ros2_control_demos +^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ + +0.1.0 (2022-05-01) +----------- +* Ignition ros2 control (`#1 `_) + Co-authored-by: ahcorde + Co-authored-by: Louise Poubel + Co-authored-by: Vatan Aksoy Tezer +* Contributors: Alejandro Hernández Cordero, Louise Poubel, Vatan Aksoy Tezer diff --git a/ignition_ros2_control_demos/CMakeLists.txt b/ign_ros2_control_demos/CMakeLists.txt similarity index 97% rename from ignition_ros2_control_demos/CMakeLists.txt rename to ign_ros2_control_demos/CMakeLists.txt index 19577c5a..bc30c724 100644 --- a/ignition_ros2_control_demos/CMakeLists.txt +++ b/ign_ros2_control_demos/CMakeLists.txt @@ -1,5 +1,5 @@ cmake_minimum_required(VERSION 3.5.0) -project(ignition_ros2_control_demos) +project(ign_ros2_control_demos) # Default to C11 if(NOT CMAKE_C_STANDARD) diff --git a/ignition_ros2_control_demos/config/cartpole_controller_effort.yaml b/ign_ros2_control_demos/config/cartpole_controller_effort.yaml similarity index 100% rename from ignition_ros2_control_demos/config/cartpole_controller_effort.yaml rename to ign_ros2_control_demos/config/cartpole_controller_effort.yaml diff --git a/ignition_ros2_control_demos/config/cartpole_controller_position.yaml b/ign_ros2_control_demos/config/cartpole_controller_position.yaml similarity index 100% rename from ignition_ros2_control_demos/config/cartpole_controller_position.yaml rename to ign_ros2_control_demos/config/cartpole_controller_position.yaml diff --git a/ignition_ros2_control_demos/config/cartpole_controller_velocity.yaml b/ign_ros2_control_demos/config/cartpole_controller_velocity.yaml similarity index 100% rename from ignition_ros2_control_demos/config/cartpole_controller_velocity.yaml rename to ign_ros2_control_demos/config/cartpole_controller_velocity.yaml diff --git a/ignition_ros2_control_demos/examples/example_effort.cpp b/ign_ros2_control_demos/examples/example_effort.cpp similarity index 100% rename from ignition_ros2_control_demos/examples/example_effort.cpp rename to ign_ros2_control_demos/examples/example_effort.cpp diff --git a/ignition_ros2_control_demos/examples/example_position.cpp b/ign_ros2_control_demos/examples/example_position.cpp similarity index 100% rename from ignition_ros2_control_demos/examples/example_position.cpp rename to ign_ros2_control_demos/examples/example_position.cpp diff --git a/ignition_ros2_control_demos/examples/example_velocity.cpp b/ign_ros2_control_demos/examples/example_velocity.cpp similarity index 100% rename from ignition_ros2_control_demos/examples/example_velocity.cpp rename to ign_ros2_control_demos/examples/example_velocity.cpp diff --git a/ignition_ros2_control_demos/launch/cart_example_effort.launch.py b/ign_ros2_control_demos/launch/cart_example_effort.launch.py similarity index 98% rename from ignition_ros2_control_demos/launch/cart_example_effort.launch.py rename to ign_ros2_control_demos/launch/cart_example_effort.launch.py index bbb0b25f..50729115 100644 --- a/ignition_ros2_control_demos/launch/cart_example_effort.launch.py +++ b/ign_ros2_control_demos/launch/cart_example_effort.launch.py @@ -34,7 +34,7 @@ def generate_launch_description(): use_sim_time = LaunchConfiguration('use_sim_time', default=True) ignition_ros2_control_demos_path = os.path.join( - get_package_share_directory('ignition_ros2_control_demos')) + get_package_share_directory('ign_ros2_control_demos')) xacro_file = os.path.join(ignition_ros2_control_demos_path, 'urdf', diff --git a/ignition_ros2_control_demos/launch/cart_example_position.launch.py b/ign_ros2_control_demos/launch/cart_example_position.launch.py similarity index 96% rename from ignition_ros2_control_demos/launch/cart_example_position.launch.py rename to ign_ros2_control_demos/launch/cart_example_position.launch.py index 71c33a41..a0c1c931 100644 --- a/ignition_ros2_control_demos/launch/cart_example_position.launch.py +++ b/ign_ros2_control_demos/launch/cart_example_position.launch.py @@ -34,7 +34,7 @@ def generate_launch_description(): use_sim_time = LaunchConfiguration('use_sim_time', default=True) ignition_ros2_control_demos_path = os.path.join( - get_package_share_directory('ignition_ros2_control_demos')) + get_package_share_directory('ign_ros2_control_demos')) xacro_file = os.path.join(ignition_ros2_control_demos_path, 'urdf', @@ -78,7 +78,7 @@ def generate_launch_description(): PythonLaunchDescriptionSource( [os.path.join(get_package_share_directory('ros_ign_gazebo'), 'launch', 'ign_gazebo.launch.py')]), - launch_arguments=[('ign_args', [' -r -v 3 empty.sdf'])]), + launch_arguments=[('ign_args', [' -r -v 4 empty.sdf'])]), RegisterEventHandler( event_handler=OnProcessExit( target_action=ignition_spawn_entity, diff --git a/ignition_ros2_control_demos/launch/cart_example_velocity.launch.py b/ign_ros2_control_demos/launch/cart_example_velocity.launch.py similarity index 98% rename from ignition_ros2_control_demos/launch/cart_example_velocity.launch.py rename to ign_ros2_control_demos/launch/cart_example_velocity.launch.py index 0544ee2a..f60cdf1e 100644 --- a/ignition_ros2_control_demos/launch/cart_example_velocity.launch.py +++ b/ign_ros2_control_demos/launch/cart_example_velocity.launch.py @@ -34,7 +34,7 @@ def generate_launch_description(): use_sim_time = LaunchConfiguration('use_sim_time', default=True) ignition_ros2_control_demos_path = os.path.join( - get_package_share_directory('ignition_ros2_control_demos')) + get_package_share_directory('ign_ros2_control_demos')) xacro_file = os.path.join(ignition_ros2_control_demos_path, 'urdf', diff --git a/ignition_ros2_control_demos/package.xml b/ign_ros2_control_demos/package.xml similarity index 91% rename from ignition_ros2_control_demos/package.xml rename to ign_ros2_control_demos/package.xml index 6673a6db..cfa17add 100644 --- a/ignition_ros2_control_demos/package.xml +++ b/ign_ros2_control_demos/package.xml @@ -1,8 +1,8 @@ - ignition_ros2_control_demos + ign_ros2_control_demos 0.0.0 - ignition_ros2_control_demos + ign_ros2_control_demos Alejandro Hernandez @@ -24,7 +24,7 @@ ament_index_python control_msgs hardware_interface - ignition_ros2_control + ign_ros2_control joint_state_broadcaster joint_trajectory_controller launch diff --git a/ignition_ros2_control_demos/urdf/test_cart_effort.xacro.urdf b/ign_ros2_control_demos/urdf/test_cart_effort.xacro.urdf similarity index 89% rename from ignition_ros2_control_demos/urdf/test_cart_effort.xacro.urdf rename to ign_ros2_control_demos/urdf/test_cart_effort.xacro.urdf index 4fa58919..3738d08f 100644 --- a/ignition_ros2_control_demos/urdf/test_cart_effort.xacro.urdf +++ b/ign_ros2_control_demos/urdf/test_cart_effort.xacro.urdf @@ -45,7 +45,7 @@ - ignition_ros2_control/IgnitionSystem + ign_ros2_control/IgnitionSystem @@ -80,8 +80,8 @@ - - $(find ignition_ros2_control_demos)/config/cartpole_controller_effort.yaml + + $(find ign_ros2_control_demos)/config/cartpole_controller_effort.yaml diff --git a/ignition_ros2_control_demos/urdf/test_cart_position.xacro.urdf b/ign_ros2_control_demos/urdf/test_cart_position.xacro.urdf similarity index 89% rename from ignition_ros2_control_demos/urdf/test_cart_position.xacro.urdf rename to ign_ros2_control_demos/urdf/test_cart_position.xacro.urdf index 6672bafd..354d35ec 100644 --- a/ignition_ros2_control_demos/urdf/test_cart_position.xacro.urdf +++ b/ign_ros2_control_demos/urdf/test_cart_position.xacro.urdf @@ -45,7 +45,7 @@ - ignition_ros2_control/IgnitionSystem + ign_ros2_control/IgnitionSystem @@ -80,8 +80,8 @@ - - $(find ignition_ros2_control_demos)/config/cartpole_controller_position.yaml + + $(find ign_ros2_control_demos)/config/cartpole_controller_position.yaml diff --git a/ignition_ros2_control_demos/urdf/test_cart_velocity.xacro.urdf b/ign_ros2_control_demos/urdf/test_cart_velocity.xacro.urdf similarity index 94% rename from ignition_ros2_control_demos/urdf/test_cart_velocity.xacro.urdf rename to ign_ros2_control_demos/urdf/test_cart_velocity.xacro.urdf index a3165dcb..59a960a1 100644 --- a/ignition_ros2_control_demos/urdf/test_cart_velocity.xacro.urdf +++ b/ign_ros2_control_demos/urdf/test_cart_velocity.xacro.urdf @@ -113,7 +113,7 @@ - ignition_ros2_control/IgnitionSystem + ign_ros2_control/IgnitionSystem @@ -160,8 +160,8 @@ - - $(find ignition_ros2_control_demos)/config/cartpole_controller_velocity.yaml + + $(find ign_ros2_control_demos)/config/cartpole_controller_velocity.yaml - - - GazeboPositionJoint - - -