Skip to content

Commit

Permalink
Merge pull request #226 from ignitionrobotics/merge78
Browse files Browse the repository at this point in the history
Merge 7 -> 8
  • Loading branch information
scpeters authored Mar 18, 2022
2 parents b41812f + aab82d8 commit 0d07350
Show file tree
Hide file tree
Showing 4 changed files with 123 additions and 6 deletions.
4 changes: 4 additions & 0 deletions .github/workflows/ci.yml
Original file line number Diff line number Diff line change
Expand Up @@ -23,6 +23,10 @@ jobs:
- name: Compile and test
id: ci
uses: ignition-tooling/action-ignition-ci@focal
with:
cppcheck-enabled: true
cpplint-enabled: true
doxygen-enabled: true
jammy-ci:
runs-on: ubuntu-latest
name: Ubuntu Jammy CI
Expand Down
40 changes: 40 additions & 0 deletions Changelog.md
Original file line number Diff line number Diff line change
Expand Up @@ -37,6 +37,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.
Expand Down Expand Up @@ -189,6 +217,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)
Expand Down
13 changes: 7 additions & 6 deletions include/ignition/msgs/PointCloudPackedUtils.hh
Original file line number Diff line number Diff line change
Expand Up @@ -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<float> 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<uint8_t> iterR(pcMsg, "r");
/// ignition::msgs::PointCloudPackedIterator<uint8_t> iterG(pcMsg, "g");
/// ignition::msgs::PointCloudPackedIterator<uint8_t> iterB(pcMsg, "b");
/// ignition::msgs::PointCloudPackedIterator<uint8_t> iterA(pcMsg, "a");
/// \endverbatim
/// \endcode
///
/// \tparam FieldType Type of the element being iterated upon
template<typename FieldType>
Expand Down
72 changes: 72 additions & 0 deletions proto/ignition/msgs/wheel_slip_parameters_cmd.proto
Original file line number Diff line number Diff line change
@@ -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;
}

0 comments on commit 0d07350

Please sign in to comment.