diff --git a/.github/workflows/ci.yml b/.github/workflows/ci.yml index da0b5b6f..b4b8a356 100644 --- a/.github/workflows/ci.yml +++ b/.github/workflows/ci.yml @@ -14,3 +14,15 @@ jobs: uses: ignition-tooling/action-ignition-ci@focal with: codecov-enabled: true + cppcheck-enabled: true + cpplint-enabled: true + doxygen-enabled: true + jammy-ci: + runs-on: ubuntu-latest + name: Ubuntu Jammy CI + steps: + - name: Checkout + uses: actions/checkout@v2 + - name: Compile and test + id: ci + uses: ignition-tooling/action-ignition-ci@jammy diff --git a/Changelog.md b/Changelog.md index 00ea8fd1..15d20c64 100644 --- a/Changelog.md +++ b/Changelog.md @@ -41,6 +41,34 @@ ## Ignition Msgs 7.x +### Ignition Msgs 7.3.0 (2022-03-17) + +1. Backport NavSat message for bridge compatibility + * [Pull request #231](https://github.com/ignitionrobotics/ign-msgs/pull/231) + +1. Focal CI: static checkers and doxygen linters + * [Pull request #230](https://github.com/ignitionrobotics/ign-msgs/pull/230) + +1. Add wheel slip message definition + * [Pull request #205](https://github.com/ignitionrobotics/ign-msgs/pull/205) + * [Pull request #227](https://github.com/ignitionrobotics/ign-msgs/pull/227) + +1. Add PointCloudPacked iterators + * [Pull request #210](https://github.com/ignitionrobotics/ign-msgs/pull/210) + * [Pull request #218](https://github.com/ignitionrobotics/ign-msgs/pull/218) + +1. Utility\_TEST: adjust expectations for 32-bit arch (#120) + * [Pull request #120) (#196](https://github.com/ignitionrobotics/ign-msgs/pull/120) (#196) + +1. Fix trivial typo in command line help message + * [Pull request #191](https://github.com/ignitionrobotics/ign-msgs/pull/191) + +1. Support colcon in windows CI + * [Pull request #189](https://github.com/ignitionrobotics/ign-msgs/pull/189) + +1. 🥳 Update ign-tools issue on README + * [Pull request #184](https://github.com/ignitionrobotics/ign-msgs/pull/184) + ### Ignition Msgs 7.2.0 (2021-09-10) 1. Adds PerformanceSensorMetrics proto message. @@ -193,6 +221,18 @@ ## Ignition Msgs 5.x +### Ignition Msgs 5.9.0 (2022-03-16) + +1. Backport NavSat message for ROS bridge compatibility + * [Pull request #231](https://github.com/ignitionrobotics/ign-msgs/pull/231) + +1. Focal CI: static checkers and doxygen linters + * [Pull request #230](https://github.com/ignitionrobotics/ign-msgs/pull/230) + +1. Add PointCloudPacked iterators + * [Pull request #210](https://github.com/ignitionrobotics/ign-msgs/pull/210) + * [Pull request #218](https://github.com/ignitionrobotics/ign-msgs/pull/218) + ### Ignition Msgs 5.8.1 (2021-10-29) 1. Utility\_TEST: adjust expectations for 32-bit arch (Backport of #120) diff --git a/include/ignition/msgs/PointCloudPackedUtils.hh b/include/ignition/msgs/PointCloudPackedUtils.hh index a2d39679..b83ad1cf 100644 --- a/include/ignition/msgs/PointCloudPackedUtils.hh +++ b/include/ignition/msgs/PointCloudPackedUtils.hh @@ -38,29 +38,30 @@ namespace msgs /// \brief Class that can iterate over a PointCloudPacked message. /// /// E.g, you create your message and reserve space for data as follows: -/// \verbatim +/// +/// \code{.cpp} /// ignition::msgs::PointCloudPacked pcMsg; /// ignition::msgs::InitPointCloudPacked(pcMsg, "my_new_frame", false, /// {{"a", PointCloudPacked::Field::FLOAT32}}); /// pcMsg.mutable_data()->resize(numPts * pcMsg.point_step()); -/// \endverbatim +/// \endcode /// /// For iterating over "a", you do : /// -/// \verbatim +/// \code{.cpp} /// ignition::msgs::PointCloudPackedIterator iterA(pcMsg, "a"); -/// \endverbatim +/// \endcode /// /// And then access it through iterA[0] or *iterA. /// /// For iterating over RGBA, you can access each element as uint8_t: /// -/// \verbatim +/// \code{.cpp} /// ignition::msgs::PointCloudPackedIterator iterR(pcMsg, "r"); /// ignition::msgs::PointCloudPackedIterator iterG(pcMsg, "g"); /// ignition::msgs::PointCloudPackedIterator iterB(pcMsg, "b"); /// ignition::msgs::PointCloudPackedIterator iterA(pcMsg, "a"); -/// \endverbatim +/// \endcode /// /// \tparam FieldType Type of the element being iterated upon template diff --git a/proto/ignition/msgs/odometry_with_covariance.proto b/proto/ignition/msgs/odometry_with_covariance.proto new file mode 100644 index 00000000..e68f4d3f --- /dev/null +++ b/proto/ignition/msgs/odometry_with_covariance.proto @@ -0,0 +1,40 @@ +/* + * 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. + * +*/ +syntax = "proto3"; +package ignition.msgs; +option java_package = "com.ignition.msgs"; +option java_outer_classname = "OdometryWithCovarianceProtos"; + +/// \ingroup ignition.msgs +/// \interface OdometryWithCovariance +/// \brief Message for odometry with covariance + +import "ignition/msgs/header.proto"; +import "ignition/msgs/pose_with_covariance.proto"; +import "ignition/msgs/twist_with_covariance.proto"; + +message OdometryWithCovariance +{ + /// \brief Optional header data. + Header header = 1; + + /// \brief Estimated pose. + PoseWithCovariance pose_with_covariance = 2; + + /// \brief Estimated linear and angular velocities. + TwistWithCovariance twist_with_covariance = 3; +} diff --git a/proto/ignition/msgs/pose_with_covariance.proto b/proto/ignition/msgs/pose_with_covariance.proto new file mode 100644 index 00000000..1e8b0fc0 --- /dev/null +++ b/proto/ignition/msgs/pose_with_covariance.proto @@ -0,0 +1,40 @@ +/* + * 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. + * +*/ + +syntax = "proto3"; +package ignition.msgs; +option java_package = "com.ignition.msgs"; +option java_outer_classname = "PoseWithCovarianceProtos"; + +/// \ingroup ignition.msgs +/// \interface PoseWithCovariance +/// \brief Message with pose and a covariance matrix + +import "ignition/msgs/float_v.proto"; +import "ignition/msgs/pose.proto"; + +message PoseWithCovariance +{ + /// \brief Pose message. + Pose pose = 1; + + /// \brief Row-major representation of the 6x6 covariance matrix + /// The orientation parameters use a fixed-axis representation. + /// In order, the parameters are: + /// (x, y, z, rotation about X axis, rotation about Y axis, rotation about Z axis) + Float_V covariance = 2; +} diff --git a/proto/ignition/msgs/twist.proto b/proto/ignition/msgs/twist.proto index c80becf5..9c247aca 100644 --- a/proto/ignition/msgs/twist.proto +++ b/proto/ignition/msgs/twist.proto @@ -32,7 +32,7 @@ message Twist /// \brief Optional header data. Header header = 1; - /// \brief Lnear velocity in 3d space. + /// \brief Linear velocity in 3d space. Vector3d linear = 2; /// \brief Angular velocity in 3d space. diff --git a/proto/ignition/msgs/twist_with_covariance.proto b/proto/ignition/msgs/twist_with_covariance.proto new file mode 100644 index 00000000..5daf37c8 --- /dev/null +++ b/proto/ignition/msgs/twist_with_covariance.proto @@ -0,0 +1,40 @@ +/* + * 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. + * +*/ + +syntax = "proto3"; +package ignition.msgs; +option java_package = "com.ignition.msgs"; +option java_outer_classname = "TwistWithCovarianceProtos"; + +/// \ingroup ignition.msgs +/// \interface TwistWithCovariance +/// \brief Message with twist and a covariance matrix + +import "ignition/msgs/float_v.proto"; +import "ignition/msgs/twist.proto"; + +message TwistWithCovariance +{ + /// \brief Twist message. + Twist twist = 1; + + /// \brief Row-major representation of the 6x6 covariance matrix + /// The orientation parameters use a fixed-axis representation. + /// In order, the parameters are: + /// (x, y, z, rotation about X axis, rotation about Y axis, rotation about Z axis) + Float_V covariance = 2; +} diff --git a/proto/ignition/msgs/wheel_slip_parameters_cmd.proto b/proto/ignition/msgs/wheel_slip_parameters_cmd.proto new file mode 100644 index 00000000..26fb399d --- /dev/null +++ b/proto/ignition/msgs/wheel_slip_parameters_cmd.proto @@ -0,0 +1,72 @@ +/* + * 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. + * +*/ + +syntax = "proto3"; +package ignition.msgs; +option java_package = "com.ignition.msgs"; +option java_outer_classname = "WheelSlipParametersCmd"; + +/// \ingroup ignition.msgs +/// \interface WheelSlipParametersCmd +/// \brief Message containing a wheel slip parameters user command. + +import "ignition/msgs/entity.proto"; +import "ignition/msgs/header.proto"; + +message WheelSlipParametersCmd +{ + /// \brief Optional header data + Header header = 1; + + /// \brief Entity which wheel slip parameters are going to be modified. + /// + /// The entity might be a model with at least one link or a link. + /// If the entity is a model, the wheel slip parameters of all its + /// links will be updated. + /// + /// The entity name (entity.name) will be used as an scoped name. + /// For example, in this + /// hierarchy: + /// + /// world_name + /// model_name + /// link_name + /// + /// All these names will return the link entity: + /// + /// * world_name::model_name::link_name + /// * model_name::link_name + /// * link_name + Entity entity = 2; + + /// \brief Unitless lateral slip ratio. + /// + /// See https://en.wikipedia.org/wiki/Slip_(vehicle_dynamics). + /// to tangential force ratio (tangential / normal force). + /// At each time step, these compliances are multiplied by + /// the linear wheel spin velocity and divided by the wheel normal force + /// parameter specified in the sdf. + double slip_compliance_lateral = 4; + /// \brief Unitless longitudinal slip ratio. + /// + /// See https://en.wikipedia.org/wiki/Slip_(vehicle_dynamics). + /// to tangential force ratio (tangential / normal force). + /// At each time step, these compliances are multiplied by + /// the linear wheel spin velocity and divided by the wheel normal force + /// parameter specified in the sdf. + double slip_compliance_longitudinal = 5; +}