Skip to content

Commit

Permalink
Merge branch 'ign-gazebo6' into aditya/odom_pub_noise
Browse files Browse the repository at this point in the history
  • Loading branch information
adityapande-1995 authored Apr 4, 2022
2 parents accb096 + 207d079 commit 309f116
Show file tree
Hide file tree
Showing 17 changed files with 1,503 additions and 3 deletions.
93 changes: 92 additions & 1 deletion Changelog.md
Original file line number Diff line number Diff line change
Expand Up @@ -556,7 +556,98 @@

## Ignition Gazebo 5.x

### Ignition Gazebo 5.X.X (202X-XX-XX)
### Ignition Gazebo 5.4.0 (2022-03-31)

1. Add the Model Photo Shoot system, port of Modelpropshop plugin from Gazebo classic
* [Pull request #1331](https://github.com/ignitionrobotics/ign-gazebo/pull/1331)

1. Add wheel slip user command
* [Pull request #1241](https://github.com/ignitionrobotics/ign-gazebo/pull/1241)

1. Added user command to set multiple entity poses
* [Pull request #1394](https://github.com/ignitionrobotics/ign-gazebo/pull/1394)

1. Component inspector: refactor Pose3d C++ code into a separate class
* [Pull request #1400](https://github.com/ignitionrobotics/ign-gazebo/pull/1400)

1. Toggle Light visuals
* [Pull request #1387](https://github.com/ignitionrobotics/ign-gazebo/pull/1387)

1. Allow to turn on/off lights
* [Pull request #1343](https://github.com/ignitionrobotics/ign-gazebo/pull/1343)

1. Added more sensor properties to scene/info topic
* [Pull request #1344](https://github.com/ignitionrobotics/ign-gazebo/pull/1344)

1. JointStatePublisher publish parent, child and axis data
* [Pull request #1345](https://github.com/ignitionrobotics/ign-gazebo/pull/1345)

1. Fixed light GUI component inspector
* [Pull request #1337](https://github.com/ignitionrobotics/ign-gazebo/pull/1337)

1. Fix `UNIT_SdfGenerator_TEST`
* [Pull request #1319](https://github.com/ignitionrobotics/ign-gazebo/pull/1319)

1. Add elevator system
* [Pull request #535](https://github.com/ignitionrobotics/ign-gazebo/pull/535)

1. Removed unused variables in shapes plugin
* [Pull request #1321](https://github.com/ignitionrobotics/ign-gazebo/pull/1321)

1. Log an error if JointPositionController cannot find the joint. (citadel retarget)
* [Pull request #1314](https://github.com/ignitionrobotics/ign-gazebo/pull/1314)

1. Buoyancy: fix center of volume's reference frame
* [Pull request #1302](https://github.com/ignitionrobotics/ign-gazebo/pull/1302)

1. Remove EachNew calls from sensor PreUpdates
* [Pull request #1281](https://github.com/ignitionrobotics/ign-gazebo/pull/1281)

1. Prevent GzScene3D 💥 if another scene is already loaded
* [Pull request #1294](https://github.com/ignitionrobotics/ign-gazebo/pull/1294)

1. Cleanup update call for non-rendering sensors
* [Pull request #1282](https://github.com/ignitionrobotics/ign-gazebo/pull/1282)

1. Documentation Error
* [Pull request #1285](https://github.com/ignitionrobotics/ign-gazebo/pull/1285)

1. Min and max parameters for velocity, acceleration, and jerk apply to linear and angular separately.
* [Pull request #1229](https://github.com/ignitionrobotics/ign-gazebo/pull/1229)

1. Add project() call to examples
* [Pull request #1274](https://github.com/ignitionrobotics/ign-gazebo/pull/1274)

1. Implement `/server_control::stop`
* [Pull request #1240](https://github.com/ignitionrobotics/ign-gazebo/pull/1240)

1. 👩‍🌾 Make depth camera tests more robust (#897)
* [Pull request #897) (#1257](https://github.com/ignitionrobotics/ign-gazebo/pull/897) (#1257)

1. Support battery draining start via topics
* [Pull request #1255](https://github.com/ignitionrobotics/ign-gazebo/pull/1255)

1. Make tests run as fast as possible
* [Pull request #1194](https://github.com/ignitionrobotics/ign-gazebo/pull/1194)
* [Pull request #1250](https://github.com/ignitionrobotics/ign-gazebo/pull/1250)

1. Fix visualize lidar
* [Pull request #1224](https://github.com/ignitionrobotics/ign-gazebo/pull/1224)

1. Skip failing Windows tests
* [Pull request #1205](https://github.com/ignitionrobotics/ign-gazebo/pull/1205)
* [Pull request #1204](https://github.com/ignitionrobotics/ign-gazebo/pull/1204)
* [Pull request #1259](https://github.com/ignitionrobotics/ign-gazebo/pull/1259)
* [Pull request #1408](https://github.com/ignitionrobotics/ign-gazebo/pull/1408)

1. Configurable joint state publisher's topic
* [Pull request #1076](https://github.com/ignitionrobotics/ign-gazebo/pull/1076)

1. Thruster plugin: add tests and velocity control
* [Pull request #1190](https://github.com/ignitionrobotics/ign-gazebo/pull/1190)

1. Limit thruster system's input thrust cmd
* [Pull request #1318](https://github.com/ignitionrobotics/ign-gazebo/pull/1318)

### Ignition Gazebo 5.3.0 (2021-11-12)

Expand Down
55 changes: 55 additions & 0 deletions examples/worlds/model_photo_shoot.sdf
Original file line number Diff line number Diff line change
@@ -0,0 +1,55 @@
<?xml version="1.0" ?>
<!--
Ignition Gazebo Model Photo Shoot plugin demo
This will take perspective, top, front, and both sides pictures of the model:
ign gazebo -s -r -v 4 \-\-iterations 50 model_photo_shoot.sdf
-->
<sdf version="1.6">
<world name="default">
<gravity>0 0 0</gravity>
<plugin
filename="ignition-gazebo-physics-system"
name="ignition::gazebo::systems::Physics">
</plugin>
<plugin
filename="ignition-gazebo-sensors-system"
name="ignition::gazebo::systems::Sensors">
<render_engine>ogre2</render_engine>
<background_color>1, 1, 1</background_color>
</plugin>
<include>
<uri>https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/Robonaut</uri>
<plugin
filename="ignition-gazebo-model-photo-shoot-system"
name="ignition::gazebo::systems::ModelPhotoShoot">
<translation_data_file>poses.txt</translation_data_file>
<random_joints_pose>false</random_joints_pose>
</plugin>
</include>
<model name="photo_shoot">
<link name="link">
<pose>0 0 0 0 0 0</pose>
<sensor name="camera" type="camera">
<camera>
<horizontal_fov>1.047</horizontal_fov>
<image>
<width>960</width>
<height>540</height>
</image>
<clip>
<near>0.1</near>
<far>100</far>
</clip>
</camera>
<always_on>1</always_on>
<update_rate>30</update_rate>
<visualize>true</visualize>
<topic>camera</topic>
</sensor>
</link>
<static>true</static>
</model>
</world>
</sdf>
46 changes: 46 additions & 0 deletions include/ignition/gazebo/components/WheelSlipCmd.hh
Original file line number Diff line number Diff line change
@@ -0,0 +1,46 @@
/*
* Copyright (C) 2022 Open Source Robotics Foundation
*
* Licensed under the Apache License, Version 2.0 (the "License");
* you may not use this file except in compliance with the License.
* You may obtain a copy of the License at
*
* http://www.apache.org/licenses/LICENSE-2.0
*
* Unless required by applicable law or agreed to in writing, software
* distributed under the License is distributed on an "AS IS" BASIS,
* WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
* See the License for the specific language governing permissions and
* limitations under the License.
*
*/
#ifndef IGNITION_GAZEBO_COMPONENTS_WHEELSLIPCMD_HH_
#define IGNITION_GAZEBO_COMPONENTS_WHEELSLIPCMD_HH_

#include <ignition/gazebo/config.hh>
#include <ignition/gazebo/Export.hh>
#include <ignition/gazebo/components/Component.hh>
#include <ignition/gazebo/components/Factory.hh>
#include <ignition/gazebo/components/Serialization.hh>

#include <ignition/msgs/wheel_slip_parameters_cmd.pb.h>

namespace ignition
{
namespace gazebo
{
// Inline bracket to help doxygen filtering.
inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE {
namespace components
{
/// \brief A component type that contains commanded wheel slip parameters of
/// an entity in the world frame represented by msgs::WheelSlipParameters.
using WheelSlipCmd = Component<ignition::msgs::WheelSlipParametersCmd,
class WheelSlipCmdTag, serializers::MsgSerializer>;
IGN_GAZEBO_REGISTER_COMPONENT("ign_gazebo_components.WheelSlipCmd",
WheelSlipCmd)
}
}
}
}
#endif
1 change: 1 addition & 0 deletions src/systems/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -126,6 +126,7 @@ add_subdirectory(log_video_recorder)
add_subdirectory(logical_audio_sensor_plugin)
add_subdirectory(logical_camera)
add_subdirectory(magnetometer)
add_subdirectory(model_photo_shoot)
add_subdirectory(mecanum_drive)
add_subdirectory(multicopter_motor_model)
add_subdirectory(multicopter_control)
Expand Down
8 changes: 8 additions & 0 deletions src/systems/model_photo_shoot/CMakeLists.txt
Original file line number Diff line number Diff line change
@@ -0,0 +1,8 @@
gz_add_system(model-photo-shoot
SOURCES
ModelPhotoShoot.cc
PUBLIC_LINK_LIBS
ignition-common${IGN_COMMON_VER}::ignition-common${IGN_COMMON_VER}
ignition-rendering${IGN_RENDERING_VER}::ignition-rendering${IGN_RENDERING_VER}
ignition-transport${IGN_TRANSPORT_VER}::ignition-transport${IGN_TRANSPORT_VER}
)
Loading

0 comments on commit 309f116

Please sign in to comment.