Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Add JointTrajectoryController system plugin #473

Merged
merged 24 commits into from
Feb 11, 2021
Merged

Add JointTrajectoryController system plugin #473

merged 24 commits into from
Feb 11, 2021

Conversation

AndrejOrsula
Copy link
Contributor

@AndrejOrsula AndrejOrsula commented Dec 3, 2020

Hello everyone,

About a month ago, I wanted to utilise MoveIt2 inside of Ignition Gazebo. At the time, I could not find anything ready-to-use that would suit my needs, so I investigated my options.
My initial plan was to employ ros2_control. However, it was still under "heavy" development last time I checked, and integrating it in a similar manner to gazebo_ros2_control is beyond my competences. Therefore, I have decided to implement JointTrajectoryController instead, bringing me to this PR.

In its simplest, JointTrajectoryController subscribes to ignition.msgs.JointTrajectory messages (PR - gazebosim/gz-msgs#106) and controls multiple single-axis joints simultaneously to follow the desired trajectory. The resulting force/torque for each joint is computed as a sum position PID commands + velocity PID commands + effort, which is then applied to joints as force/torque commands. Any of these terms can be ignored by a) disabling PID; b) not including the corresponding commands in the JointTrajectory message. This allows the plugin to be used without a motion planning framework like MoveIt, e.g. for direct effort control of a manipulator or a simple gripper, which can even be in real-time if JointTrajectory is published frequently with only a single point.

I am not really sure if this plugin fits here or there is something else designed to obtain a similar functionality. If integration with ros2_control is preferred, or there are some other plans to obtain such functionality, then feel free to close this PR 😄.


Examples: An example of using MoveIt2 to control Franka Emika Panda can be seen under ign_moveit2. Below is a small animation of utilising this plugin control all joints, including the gripper.

ign_moveit2_throw

Inclusion in SDF (example with Franka Emika Panda):

<include>
    <uri>https://fuel.ignitionrobotics.org/1.0/AndrejOrsula/models/panda</uri>
    <plugin 
        filename="libignition-gazebo-joint-trajectory-controller-system.so"
        name="ignition::gazebo::systems::JointTrajectoryController">
        <joint_name>panda_joint1</joint_name>
        <initial_position>0</initial_position>
        <position_p_gain>3000</position_p_gain>
        <position_d_gain>15</position_d_gain>
        <position_i_gain>1650</position_i_gain>
        <position_i_min>-15</position_i_min>
        <position_i_max>15</position_i_max>
        <position_cmd_min>-87</position_cmd_min>
        <position_cmd_max>87</position_cmd_max>

        <joint_name>panda_joint2</joint_name>
        <initial_position>0</initial_position>
        <position_p_gain>9500</position_p_gain>
        <position_d_gain>47.5</position_d_gain>
        <position_i_gain>5225</position_i_gain>
        <position_i_min>-47.5</position_i_min>
        <position_i_max>47.5</position_i_max>
        <position_cmd_min>-87</position_cmd_min>
        <position_cmd_max>87</position_cmd_max>

        <joint_name>panda_joint3</joint_name>
        <initial_position>0</initial_position>
        <position_p_gain>6500</position_p_gain>
        <position_d_gain>32.5</position_d_gain>
        <position_i_gain>3575</position_i_gain>
        <position_i_min>-32.5</position_i_min>
        <position_i_max>32.5</position_i_max>
        <position_cmd_min>-87</position_cmd_min>
        <position_cmd_max>87</position_cmd_max>

        <joint_name>panda_joint4</joint_name>
        <initial_position>-1.57</initial_position>
        <position_p_gain>6000</position_p_gain>
        <position_d_gain>30</position_d_gain>
        <position_i_gain>3300</position_i_gain>
        <position_i_min>-30</position_i_min>
        <position_i_max>30</position_i_max>
        <position_cmd_min>-87</position_cmd_min>
        <position_cmd_max>87</position_cmd_max>

        <joint_name>panda_joint5</joint_name>
        <initial_position>0</initial_position>
        <position_p_gain>2750</position_p_gain>
        <position_d_gain>2.75</position_d_gain>
        <position_i_gain>1515</position_i_gain>
        <position_i_min>-6.88</position_i_min>
        <position_i_max>6.88</position_i_max>
        <position_cmd_min>-12</position_cmd_min>
        <position_cmd_max>12</position_cmd_max>

        <joint_name>panda_joint6</joint_name>
        <initial_position>1.57</initial_position>
        <position_p_gain>2500</position_p_gain>
        <position_d_gain>2.5</position_d_gain>
        <position_i_gain>1375</position_i_gain>
        <position_i_min>-6.25</position_i_min>
        <position_i_max>6.25</position_i_max>
        <position_cmd_min>-12</position_cmd_min>
        <position_cmd_max>12</position_cmd_max>

        <joint_name>panda_joint7</joint_name>
        <initial_position>0.79</initial_position>
        <position_p_gain>2000</position_p_gain>
        <position_d_gain>2</position_d_gain>
        <position_i_gain>1100</position_i_gain>
        <position_i_min>-5</position_i_min>
        <position_i_max>5</position_i_max>
        <position_cmd_min>-12</position_cmd_min>
        <position_cmd_max>12</position_cmd_max>

        <joint_name>panda_finger_joint1</joint_name>
        <initial_position>0</initial_position>
        <position_p_gain>250</position_p_gain>
        <position_d_gain>0.2</position_d_gain>
        <position_i_gain>50</position_i_gain>
        <position_i_min>-10</position_i_min>
        <position_i_max>10</position_i_max>
        <position_cmd_min>-20</position_cmd_min>
        <position_cmd_max>20</position_cmd_max>

        <joint_name>panda_finger_joint2</joint_name>
        <initial_position>0</initial_position>
        <position_p_gain>250</position_p_gain>
        <position_d_gain>0.2</position_d_gain>
        <position_i_gain>50</position_i_gain>
        <position_i_min>-10</position_i_min>
        <position_i_max>10</position_i_max>
        <position_cmd_min>-20</position_cmd_min>
        <position_cmd_max>20</position_cmd_max>
    </plugin>
</include>

JointTrajectoryController.hh documents this further.

Signed-off-by: Andrej Orsula <orsula.andrej@gmail.com>
Signed-off-by: Andrej Orsula <orsula.andrej@gmail.com>
@chapulina chapulina self-assigned this Dec 7, 2020
@chapulina chapulina moved this from Inbox to In review in Core development Dec 7, 2020
@chapulina chapulina added the needs upstream release Blocked by a release of an upstream library label Dec 7, 2020
Signed-off-by: Andrej Orsula <orsula.andrej@gmail.com>
Signed-off-by: Andrej Orsula <orsula.andrej@gmail.com>
Signed-off-by: Andrej Orsula <orsula.andrej@gmail.com>
Copy link
Contributor

@chapulina chapulina left a comment

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Thank you for the PR! The new plugin seems like a superset of the existing JointController plugin, so my initial impulse was to suggest targeting the new functionality at the old plugin. But while looking at the implementation, I think that this adds enough to deserve being its own plugin, and we leave the other one as a simpler implementation that handles one command at a time.

Unfortunately, I have not added any automated tests with this PR.

It would be good to add a test before merging, we want to make sure that the plugin continues working. Would it be possible to add a simple test similar to INTEGRATION_joint_controller_system? Covering all features would be great, but just a couple of use cases would also be helpful.

Fails because it is not using fork of ign-msgs

ign-msgs 6.2.0 was released with the new message, so the next time you push to this PR, CI should be fixed. Please also be sure to bump the required ign-msgs version here:

https://github.com/ignitionrobotics/ign-gazebo/blob/a830b443989877b1e83170390f483b6c02952b25/CMakeLists.txt#L56


It's awesome that you have a package demonstrating how to use this with MoveIt2! It would be nice to add a simple demo using just Ignition Gazebo too. We usually add worlds to the example/worlds folder with some instructions on the top. See joint_controller.sdf for example. You could add an example that sends a couple of trajectory points from the command line, just to exercise the plugin.

Signed-off-by: Andrej Orsula <orsula.andrej@gmail.com>
Signed-off-by: Andrej Orsula <orsula.andrej@gmail.com>
Signed-off-by: Andrej Orsula <orsula.andrej@gmail.com>
Signed-off-by: Andrej Orsula <orsula.andrej@gmail.com>
Signed-off-by: Andrej Orsula <orsula.andrej@gmail.com>
Signed-off-by: Andrej Orsula <orsula.andrej@gmail.com>
Signed-off-by: Andrej Orsula <orsula.andrej@gmail.com>
Signed-off-by: Andrej Orsula <orsula.andrej@gmail.com>
Signed-off-by: Andrej Orsula <orsula.andrej@gmail.com>
Signed-off-by: Andrej Orsula <orsula.andrej@gmail.com>
Signed-off-by: Andrej Orsula <orsula.andrej@gmail.com>
Signed-off-by: Andrej Orsula <orsula.andrej@gmail.com>
Signed-off-by: Andrej Orsula <orsula.andrej@gmail.com>
Signed-off-by: Andrej Orsula <orsula.andrej@gmail.com>
Signed-off-by: Andrej Orsula <orsula.andrej@gmail.com>
@AndrejOrsula
Copy link
Contributor Author

It would be good to add a test before merging

Added tests for position and velocity control. PID/PI gains were tuned to have somewhat aggressive response in order to reduce the necessary duration of the test. Both should succeed with tolerance of 1e-5 (position even with 1e-6), but I set it to 1e-4 in case there are some minor/negligible future changes in physics.

These tests should* cover the main functionality of the plugin, parsing of parameters and communication via Ignition Transport. I did not add any complicated case of hybrid control as I wasn't really sure how to design such test.

It would be nice to add a simple demo using just Ignition Gazebo

Added a simple world with three planar RR robots to demonstrate position, velocity and effort control. Sending joint trajectories with CLI is a bit messy but I hope that's okay.

@AndrejOrsula
Copy link
Contributor Author

Just a few thoughts for future. I have not included them, but they could be implemented as optional features of the plugin and enabled via parameters.

Use JointPositionReset component to set initial_position of joints

Currently, this plugin uses initial_position just as the first position target that the joint should reach. If position control is not enabled, this property is more or less ignored. JointPositionReset component could therefore be used to set the joint positions right after the model is spawned (inside Configure() if possible or at the first call to PreUpdate() and at each reset) and then just maintain them with regular control.

Add interpolation between trajectory points to provide smoother motion and reach points exactly at their time_from_start

This plugin currently does not perform any interpolation, therefore, the produced motion will be only as smooth as the input joint trajectory. With sparse points such as those in demo, it is possible to tune the smoothness a bit with the combination of PID gains and joint dynamics (e.g. damping), but it is quite limited.

Although some motion planning frameworks, e.g. MoveIt, might already produce trajectories with configurable number of points via their own interpolation/parameterization, it might still be beneficial to add simple interpolation inside of this plugin.

@codecov
Copy link

codecov bot commented Jan 5, 2021

Codecov Report

Merging #473 (a830b44) into ign-gazebo4 (2a25fc7) will increase coverage by 0.32%.
The diff coverage is 85.58%.

Impacted file tree graph

@@               Coverage Diff               @@
##           ign-gazebo4     #473      +/-   ##
===============================================
+ Coverage        77.29%   77.61%   +0.32%     
===============================================
  Files              208      213       +5     
  Lines            11198    11624     +426     
===============================================
+ Hits              8655     9022     +367     
- Misses            2543     2602      +59     
Impacted Files Coverage Δ
...e/ignition/gazebo/detail/EntityComponentManager.hh 95.00% <ø> (ø)
include/ignition/gazebo/gui/GuiRunner.hh 100.00% <ø> (ø)
src/SimulationRunner.hh 100.00% <ø> (ø)
src/gui/plugins/entity_tree/EntityTree.hh 100.00% <ø> (ø)
.../gui/plugins/transform_control/TransformControl.hh 100.00% <ø> (ø)
src/ign.cc 72.18% <ø> (ø)
src/systems/buoyancy/Buoyancy.cc 75.28% <ø> (ø)
src/systems/diff_drive/DiffDrive.cc 84.10% <ø> (ø)
src/systems/follow_actor/FollowActor.cc 57.00% <ø> (ø)
src/systems/physics/Physics.cc 71.44% <ø> (ø)
... and 17 more

Continue to review full report at Codecov.

Legend - Click here to learn more
Δ = absolute <relative> (impact), ø = not affected, ? = missing data
Powered by Codecov. Last update efe8ea1...c462446. Read the comment docs.

@chapulina chapulina removed the needs upstream release Blocked by a release of an upstream library label Jan 23, 2021
Signed-off-by: Louise Poubel <louise@openrobotics.org>
Copy link
Contributor

@chapulina chapulina left a comment

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

This works great, thanks again for the PR! I love the demo world! Just waiting on CI results to merge.

joint_trajectory_controller

Copy link
Contributor

@chapulina chapulina left a comment

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

The code checker has several complaints, mind addressing those? You can try locally with make codecheck:

Codecheck warnings
2021-02-10T02:56:23.3810134Z /github/workspace/src/systems/joint_trajectory_controller/JointTrajectoryController.cc:44:  Line ends in whitespace.  Consider deleting these extra spaces.  [whitespace/end_of_line] [4]
2021-02-10T02:56:23.3815770Z /github/workspace/src/systems/joint_trajectory_controller/JointTrajectoryController.cc:44:  Lines should be <= 80 characters long  [whitespace/line_length] [2]
2021-02-10T02:56:23.3817456Z /github/workspace/src/systems/joint_trajectory_controller/JointTrajectoryController.cc:48:  Lines should be <= 80 characters long  [whitespace/line_length] [2]
2021-02-10T02:56:23.3819131Z /github/workspace/src/systems/joint_trajectory_controller/JointTrajectoryController.cc:51:  Lines should be <= 80 characters long  [whitespace/line_length] [2]
2021-02-10T02:56:23.3821090Z /github/workspace/src/systems/joint_trajectory_controller/JointTrajectoryController.cc:52:  Lines should be <= 80 characters long  [whitespace/line_length] [2]
2021-02-10T02:56:23.3822731Z /github/workspace/src/systems/joint_trajectory_controller/JointTrajectoryController.cc:58:  Lines should be <= 80 characters long  [whitespace/line_length] [2]
2021-02-10T02:56:23.3824321Z /github/workspace/src/systems/joint_trajectory_controller/JointTrajectoryController.cc:60:  Lines should be <= 80 characters long  [whitespace/line_length] [2]
2021-02-10T02:56:23.3825918Z /github/workspace/src/systems/joint_trajectory_controller/JointTrajectoryController.cc:63:  Lines should be <= 80 characters long  [whitespace/line_length] [2]
2021-02-10T02:56:23.3827508Z /github/workspace/src/systems/joint_trajectory_controller/JointTrajectoryController.cc:66:  Lines should be <= 80 characters long  [whitespace/line_length] [2]
2021-02-10T02:56:23.3829263Z /github/workspace/src/systems/joint_trajectory_controller/JointTrajectoryController.cc:71:  Lines should be <= 80 characters long  [whitespace/line_length] [2]
2021-02-10T02:56:23.3830919Z /github/workspace/src/systems/joint_trajectory_controller/JointTrajectoryController.cc:72:  Lines should be <= 80 characters long  [whitespace/line_length] [2]
2021-02-10T02:56:23.3832814Z /github/workspace/src/systems/joint_trajectory_controller/JointTrajectoryController.cc:74:  Lines should be <= 80 characters long  [whitespace/line_length] [2]
2021-02-10T02:56:23.3834464Z /github/workspace/src/systems/joint_trajectory_controller/JointTrajectoryController.cc:126:  Lines should be <= 80 characters long  [whitespace/line_length] [2]
2021-02-10T02:56:23.3836210Z /github/workspace/src/systems/joint_trajectory_controller/JointTrajectoryController.cc:134:  Lines should be <= 80 characters long  [whitespace/line_length] [2]
2021-02-10T02:56:23.3837800Z /github/workspace/src/systems/joint_trajectory_controller/JointTrajectoryController.cc:140:  Lines should be <= 80 characters long  [whitespace/line_length] [2]
2021-02-10T02:56:23.3839587Z /github/workspace/src/systems/joint_trajectory_controller/JointTrajectoryController.cc:144:  Lines should be <= 80 characters long  [whitespace/line_length] [2]
2021-02-10T02:56:23.3841249Z /github/workspace/src/systems/joint_trajectory_controller/JointTrajectoryController.cc:146:  Lines should be <= 80 characters long  [whitespace/line_length] [2]
2021-02-10T02:56:23.3842893Z /github/workspace/src/systems/joint_trajectory_controller/JointTrajectoryController.cc:191:  Lines should be <= 80 characters long  [whitespace/line_length] [2]
2021-02-10T02:56:23.3844637Z /github/workspace/src/systems/joint_trajectory_controller/JointTrajectoryController.cc:194:  Lines should be <= 80 characters long  [whitespace/line_length] [2]
2021-02-10T02:56:23.3846402Z /github/workspace/src/systems/joint_trajectory_controller/JointTrajectoryController.cc:198:  Lines should be <= 80 characters long  [whitespace/line_length] [2]
2021-02-10T02:56:23.3848064Z /github/workspace/src/systems/joint_trajectory_controller/JointTrajectoryController.cc:208:  Lines should be <= 80 characters long  [whitespace/line_length] [2]
2021-02-10T02:56:23.3850355Z /github/workspace/src/systems/joint_trajectory_controller/JointTrajectoryController.cc:215:  Lines should be <= 80 characters long  [whitespace/line_length] [2]
2021-02-10T02:56:23.3852119Z /github/workspace/src/systems/joint_trajectory_controller/JointTrajectoryController.cc:229:  Lines should be <= 80 characters long  [whitespace/line_length] [2]
2021-02-10T02:56:23.3853777Z /github/workspace/src/systems/joint_trajectory_controller/JointTrajectoryController.cc:232:  Lines should be <= 80 characters long  [whitespace/line_length] [2]
2021-02-10T02:56:23.3855682Z /github/workspace/src/systems/joint_trajectory_controller/JointTrajectoryController.cc:240:  Lines should be <= 80 characters long  [whitespace/line_length] [2]
2021-02-10T02:56:23.3857332Z /github/workspace/src/systems/joint_trajectory_controller/JointTrajectoryController.cc:241:  Lines should be <= 80 characters long  [whitespace/line_length] [2]
2021-02-10T02:56:23.3859186Z /github/workspace/src/systems/joint_trajectory_controller/JointTrajectoryController.cc:242:  Lines should be <= 80 characters long  [whitespace/line_length] [2]
2021-02-10T02:56:23.3860860Z /github/workspace/src/systems/joint_trajectory_controller/JointTrajectoryController.cc:247:  Lines should be <= 80 characters long  [whitespace/line_length] [2]
2021-02-10T02:56:23.3862521Z /github/workspace/src/systems/joint_trajectory_controller/JointTrajectoryController.cc:248:  Lines should be <= 80 characters long  [whitespace/line_length] [2]
2021-02-10T02:56:23.3864172Z /github/workspace/src/systems/joint_trajectory_controller/JointTrajectoryController.cc:251:  Lines should be <= 80 characters long  [whitespace/line_length] [2]
2021-02-10T02:56:23.3866035Z /github/workspace/src/systems/joint_trajectory_controller/JointTrajectoryController.cc:252:  Lines should be <= 80 characters long  [whitespace/line_length] [2]
2021-02-10T02:56:23.3867692Z /github/workspace/src/systems/joint_trajectory_controller/JointTrajectoryController.cc:254:  Lines should be <= 80 characters long  [whitespace/line_length] [2]
2021-02-10T02:56:23.3869353Z /github/workspace/src/systems/joint_trajectory_controller/JointTrajectoryController.cc:263:  Lines should be <= 80 characters long  [whitespace/line_length] [2]
2021-02-10T02:56:23.3871004Z /github/workspace/src/systems/joint_trajectory_controller/JointTrajectoryController.cc:272:  Lines should be <= 80 characters long  [whitespace/line_length] [2]
2021-02-10T02:56:23.3872662Z /github/workspace/src/systems/joint_trajectory_controller/JointTrajectoryController.cc:276:  Lines should be <= 80 characters long  [whitespace/line_length] [2]
2021-02-10T02:56:23.3874300Z /github/workspace/src/systems/joint_trajectory_controller/JointTrajectoryController.cc:292:  Lines should be <= 80 characters long  [whitespace/line_length] [2]
2021-02-10T02:56:23.3875993Z /github/workspace/src/systems/joint_trajectory_controller/JointTrajectoryController.cc:300:  Lines should be <= 80 characters long  [whitespace/line_length] [2]
2021-02-10T02:56:23.3877646Z /github/workspace/src/systems/joint_trajectory_controller/JointTrajectoryController.cc:301:  Lines should be <= 80 characters long  [whitespace/line_length] [2]
2021-02-10T02:56:23.3879305Z /github/workspace/src/systems/joint_trajectory_controller/JointTrajectoryController.cc:302:  Lines should be <= 80 characters long  [whitespace/line_length] [2]
2021-02-10T02:56:23.3880942Z /github/workspace/src/systems/joint_trajectory_controller/JointTrajectoryController.cc:305:  Lines should be <= 80 characters long  [whitespace/line_length] [2]
2021-02-10T02:56:23.3882598Z /github/workspace/src/systems/joint_trajectory_controller/JointTrajectoryController.cc:309:  Lines should be <= 80 characters long  [whitespace/line_length] [2]
2021-02-10T02:56:23.3884253Z /github/workspace/src/systems/joint_trajectory_controller/JointTrajectoryController.cc:317:  Lines should be <= 80 characters long  [whitespace/line_length] [2]
2021-02-10T02:56:23.3886000Z /github/workspace/src/systems/joint_trajectory_controller/JointTrajectoryController.cc:319:  Lines should be <= 80 characters long  [whitespace/line_length] [2]
2021-02-10T02:56:23.3887655Z /github/workspace/src/systems/joint_trajectory_controller/JointTrajectoryController.cc:320:  Lines should be <= 80 characters long  [whitespace/line_length] [2]
2021-02-10T02:56:23.3889301Z /github/workspace/src/systems/joint_trajectory_controller/JointTrajectoryController.cc:327:  Lines should be <= 80 characters long  [whitespace/line_length] [2]
2021-02-10T02:56:23.3890959Z /github/workspace/src/systems/joint_trajectory_controller/JointTrajectoryController.cc:335:  Lines should be <= 80 characters long  [whitespace/line_length] [2]
2021-02-10T02:56:23.3892597Z /github/workspace/src/systems/joint_trajectory_controller/JointTrajectoryController.cc:350:  Lines should be <= 80 characters long  [whitespace/line_length] [2]
2021-02-10T02:56:23.3894460Z /github/workspace/src/systems/joint_trajectory_controller/JointTrajectoryController.cc:353:  Lines should be <= 80 characters long  [whitespace/line_length] [2]
2021-02-10T02:56:23.3896133Z /github/workspace/src/systems/joint_trajectory_controller/JointTrajectoryController.cc:358:  Lines should be <= 80 characters long  [whitespace/line_length] [2]
2021-02-10T02:56:23.3897794Z /github/workspace/src/systems/joint_trajectory_controller/JointTrajectoryController.cc:361:  Lines should be <= 80 characters long  [whitespace/line_length] [2]
2021-02-10T02:56:23.3899432Z /github/workspace/src/systems/joint_trajectory_controller/JointTrajectoryController.cc:366:  Lines should be <= 80 characters long  [whitespace/line_length] [2]
2021-02-10T02:56:23.4498997Z /github/workspace/src/systems/joint_trajectory_controller/JointTrajectoryController.cc:368:  Lines should be <= 80 characters long  [whitespace/line_length] [2]
2021-02-10T02:56:23.4501249Z /github/workspace/src/systems/joint_trajectory_controller/JointTrajectoryController.cc:372:  Lines should be <= 80 characters long  [whitespace/line_length] [2]
2021-02-10T02:56:23.4503455Z /github/workspace/src/systems/joint_trajectory_controller/JointTrajectoryController.cc:373:  Lines should be <= 80 characters long  [whitespace/line_length] [2]
2021-02-10T02:56:23.4505374Z /github/workspace/src/systems/joint_trajectory_controller/JointTrajectoryController.cc:391:  Lines should be <= 80 characters long  [whitespace/line_length] [2]
2021-02-10T02:56:23.4507274Z /github/workspace/src/systems/joint_trajectory_controller/JointTrajectoryController.cc:439:  Lines should be <= 80 characters long  [whitespace/line_length] [2]
2021-02-10T02:56:23.4509183Z /github/workspace/src/systems/joint_trajectory_controller/JointTrajectoryController.cc:440:  Lines should be <= 80 characters long  [whitespace/line_length] [2]
2021-02-10T02:56:23.4511075Z /github/workspace/src/systems/joint_trajectory_controller/JointTrajectoryController.cc:442:  Lines should be <= 80 characters long  [whitespace/line_length] [2]
2021-02-10T02:56:23.4512999Z /github/workspace/src/systems/joint_trajectory_controller/JointTrajectoryController.cc:443:  Lines should be <= 80 characters long  [whitespace/line_length] [2]
2021-02-10T02:56:23.4514967Z /github/workspace/src/systems/joint_trajectory_controller/JointTrajectoryController.cc:444:  Lines should be <= 80 characters long  [whitespace/line_length] [2]
2021-02-10T02:56:23.4516789Z /github/workspace/src/systems/joint_trajectory_controller/JointTrajectoryController.cc:457:  Lines should be <= 80 characters long  [whitespace/line_length] [2]
2021-02-10T02:56:23.4519699Z /github/workspace/src/systems/joint_trajectory_controller/JointTrajectoryController.cc:491:  Lines should be <= 80 characters long  [whitespace/line_length] [2]
2021-02-10T02:56:23.4521843Z /github/workspace/src/systems/joint_trajectory_controller/JointTrajectoryController.cc:502:  Lines should be <= 80 characters long  [whitespace/line_length] [2]
2021-02-10T02:56:23.4523665Z /github/workspace/src/systems/joint_trajectory_controller/JointTrajectoryController.cc:506:  Lines should be <= 80 characters long  [whitespace/line_length] [2]
2021-02-10T02:56:23.4525758Z /github/workspace/src/systems/joint_trajectory_controller/JointTrajectoryController.cc:512:  Lines should be <= 80 characters long  [whitespace/line_length] [2]
2021-02-10T02:56:23.4527774Z /github/workspace/src/systems/joint_trajectory_controller/JointTrajectoryController.cc:513:  Lines should be <= 80 characters long  [whitespace/line_length] [2]
2021-02-10T02:56:23.4529559Z /github/workspace/src/systems/joint_trajectory_controller/JointTrajectoryController.cc:528:  Lines should be <= 80 characters long  [whitespace/line_length] [2]
2021-02-10T02:56:23.4531359Z /github/workspace/src/systems/joint_trajectory_controller/JointTrajectoryController.cc:535:  Lines should be <= 80 characters long  [whitespace/line_length] [2]
2021-02-10T02:56:23.4533390Z /github/workspace/src/systems/joint_trajectory_controller/JointTrajectoryController.cc:541:  Lines should be <= 80 characters long  [whitespace/line_length] [2]
2021-02-10T02:56:23.4535540Z /github/workspace/src/systems/joint_trajectory_controller/JointTrajectoryController.cc:555:  Lines should be <= 80 characters long  [whitespace/line_length] [2]
2021-02-10T02:56:23.4537400Z /github/workspace/src/systems/joint_trajectory_controller/JointTrajectoryController.cc:564:  Lines should be <= 80 characters long  [whitespace/line_length] [2]
2021-02-10T02:56:23.4539202Z /github/workspace/src/systems/joint_trajectory_controller/JointTrajectoryController.cc:565:  Lines should be <= 80 characters long  [whitespace/line_length] [2]
2021-02-10T02:56:23.4541004Z /github/workspace/src/systems/joint_trajectory_controller/JointTrajectoryController.cc:570:  Lines should be <= 80 characters long  [whitespace/line_length] [2]
2021-02-10T02:56:23.4542798Z /github/workspace/src/systems/joint_trajectory_controller/JointTrajectoryController.cc:588:  Lines should be <= 80 characters long  [whitespace/line_length] [2]
2021-02-10T02:56:23.4546749Z /github/workspace/src/systems/joint_trajectory_controller/JointTrajectoryController.cc:593:  Lines should be <= 80 characters long  [whitespace/line_length] [2]
2021-02-10T02:56:23.4548415Z /github/workspace/src/systems/joint_trajectory_controller/JointTrajectoryController.cc:596:  Lines should be <= 80 characters long  [whitespace/line_length] [2]
2021-02-10T02:56:23.4556575Z /github/workspace/src/systems/joint_trajectory_controller/JointTrajectoryController.cc:605:  Lines should be <= 80 characters long  [whitespace/line_length] [2]
2021-02-10T02:56:23.4558240Z /github/workspace/src/systems/joint_trajectory_controller/JointTrajectoryController.cc:610:  Lines should be <= 80 characters long  [whitespace/line_length] [2]
2021-02-10T02:56:23.4560013Z /github/workspace/src/systems/joint_trajectory_controller/JointTrajectoryController.cc:615:  Lines should be <= 80 characters long  [whitespace/line_length] [2]
2021-02-10T02:56:23.4561775Z /github/workspace/src/systems/joint_trajectory_controller/JointTrajectoryController.cc:616:  Lines should be <= 80 characters long  [whitespace/line_length] [2]
2021-02-10T02:56:23.4563434Z /github/workspace/src/systems/joint_trajectory_controller/JointTrajectoryController.cc:666:  Lines should be <= 80 characters long  [whitespace/line_length] [2]
2021-02-10T02:56:23.4565087Z /github/workspace/src/systems/joint_trajectory_controller/JointTrajectoryController.cc:668:  Lines should be <= 80 characters long  [whitespace/line_length] [2]
2021-02-10T02:56:23.4566734Z /github/workspace/src/systems/joint_trajectory_controller/JointTrajectoryController.cc:669:  Lines should be <= 80 characters long  [whitespace/line_length] [2]
2021-02-10T02:56:23.4568504Z /github/workspace/src/systems/joint_trajectory_controller/JointTrajectoryController.cc:670:  Lines should be <= 80 characters long  [whitespace/line_length] [2]
2021-02-10T02:56:23.4570226Z /github/workspace/src/systems/joint_trajectory_controller/JointTrajectoryController.cc:671:  Lines should be <= 80 characters long  [whitespace/line_length] [2]
2021-02-10T02:56:23.4572069Z /github/workspace/src/systems/joint_trajectory_controller/JointTrajectoryController.cc:672:  Lines should be <= 80 characters long  [whitespace/line_length] [2]
2021-02-10T02:56:23.4573842Z /github/workspace/src/systems/joint_trajectory_controller/JointTrajectoryController.cc:673:  Lines should be <= 80 characters long  [whitespace/line_length] [2]
2021-02-10T02:56:23.4575539Z /github/workspace/src/systems/joint_trajectory_controller/JointTrajectoryController.cc:674:  Lines should be <= 80 characters long  [whitespace/line_length] [2]
2021-02-10T02:56:23.4577188Z /github/workspace/src/systems/joint_trajectory_controller/JointTrajectoryController.cc:675:  Lines should be <= 80 characters long  [whitespace/line_length] [2]
2021-02-10T02:56:23.4578849Z /github/workspace/src/systems/joint_trajectory_controller/JointTrajectoryController.cc:677:  Lines should be <= 80 characters long  [whitespace/line_length] [2]
2021-02-10T02:56:23.4580606Z /github/workspace/src/systems/joint_trajectory_controller/JointTrajectoryController.cc:678:  Lines should be <= 80 characters long  [whitespace/line_length] [2]
2021-02-10T02:56:23.4582283Z /github/workspace/src/systems/joint_trajectory_controller/JointTrajectoryController.cc:679:  Lines should be <= 80 characters long  [whitespace/line_length] [2]
2021-02-10T02:56:23.4583931Z /github/workspace/src/systems/joint_trajectory_controller/JointTrajectoryController.cc:680:  Lines should be <= 80 characters long  [whitespace/line_length] [2]
2021-02-10T02:56:23.4585587Z /github/workspace/src/systems/joint_trajectory_controller/JointTrajectoryController.cc:681:  Lines should be <= 80 characters long  [whitespace/line_length] [2]
2021-02-10T02:56:23.4587231Z /github/workspace/src/systems/joint_trajectory_controller/JointTrajectoryController.cc:682:  Lines should be <= 80 characters long  [whitespace/line_length] [2]
2021-02-10T02:56:23.4588886Z /github/workspace/src/systems/joint_trajectory_controller/JointTrajectoryController.cc:683:  Lines should be <= 80 characters long  [whitespace/line_length] [2]
2021-02-10T02:56:23.4590541Z /github/workspace/src/systems/joint_trajectory_controller/JointTrajectoryController.cc:684:  Lines should be <= 80 characters long  [whitespace/line_length] [2]
2021-02-10T02:56:23.4592198Z /github/workspace/src/systems/joint_trajectory_controller/JointTrajectoryController.cc:690:  Lines should be <= 80 characters long  [whitespace/line_length] [2]
2021-02-10T02:56:23.4593840Z /github/workspace/src/systems/joint_trajectory_controller/JointTrajectoryController.cc:693:  Lines should be <= 80 characters long  [whitespace/line_length] [2]
2021-02-10T02:56:23.4595500Z /github/workspace/src/systems/joint_trajectory_controller/JointTrajectoryController.cc:695:  Lines should be <= 80 characters long  [whitespace/line_length] [2]
2021-02-10T02:56:23.4597403Z /github/workspace/src/systems/joint_trajectory_controller/JointTrajectoryController.cc:697:  Lines should be <= 80 characters long  [whitespace/line_length] [2]
2021-02-10T02:56:23.4599069Z /github/workspace/src/systems/joint_trajectory_controller/JointTrajectoryController.cc:699:  Lines should be <= 80 characters long  [whitespace/line_length] [2]
2021-02-10T02:56:29.6823472Z /github/workspace/src/systems/joint_trajectory_controller/JointTrajectoryController.cc:701:  Lines should be <= 80 characters long  [whitespace/line_length] [2]
2021-02-10T02:56:29.6830600Z /github/workspace/src/systems/joint_trajectory_controller/JointTrajectoryController.cc:703:  Lines should be <= 80 characters long  [whitespace/line_length] [2]
2021-02-10T02:56:29.6832791Z /github/workspace/src/systems/joint_trajectory_controller/JointTrajectoryController.cc:705:  Lines should be <= 80 characters long  [whitespace/line_length] [2]
2021-02-10T02:56:29.6835072Z /github/workspace/src/systems/joint_trajectory_controller/JointTrajectoryController.cc:707:  Lines should be <= 80 characters long  [whitespace/line_length] [2]
2021-02-10T02:56:29.6837343Z /github/workspace/src/systems/joint_trajectory_controller/JointTrajectoryController.cc:710:  Lines should be <= 80 characters long  [whitespace/line_length] [2]
2021-02-10T02:56:29.7448475Z /github/workspace/src/systems/joint_trajectory_controller/JointTrajectoryController.cc:712:  Lines should be <= 80 characters long  [whitespace/line_length] [2]
2021-02-10T02:56:29.7450150Z /github/workspace/src/systems/joint_trajectory_controller/JointTrajectoryController.cc:714:  Lines should be <= 80 characters long  [whitespace/line_length] [2]
2021-02-10T02:56:29.7452067Z /github/workspace/src/systems/joint_trajectory_controller/JointTrajectoryController.cc:716:  Lines should be <= 80 characters long  [whitespace/line_length] [2]
2021-02-10T02:56:29.7453866Z /github/workspace/src/systems/joint_trajectory_controller/JointTrajectoryController.cc:718:  Lines should be <= 80 characters long  [whitespace/line_length] [2]
2021-02-10T02:56:29.7455642Z /github/workspace/src/systems/joint_trajectory_controller/JointTrajectoryController.cc:720:  Lines should be <= 80 characters long  [whitespace/line_length] [2]
2021-02-10T02:56:29.7457463Z /github/workspace/src/systems/joint_trajectory_controller/JointTrajectoryController.cc:722:  Lines should be <= 80 characters long  [whitespace/line_length] [2]
2021-02-10T02:56:29.7459149Z /github/workspace/src/systems/joint_trajectory_controller/JointTrajectoryController.cc:724:  Lines should be <= 80 characters long  [whitespace/line_length] [2]
2021-02-10T02:56:29.7460801Z /github/workspace/src/systems/joint_trajectory_controller/JointTrajectoryController.cc:726:  Lines should be <= 80 characters long  [whitespace/line_length] [2]
2021-02-10T02:56:29.7462491Z /github/workspace/src/systems/joint_trajectory_controller/JointTrajectoryController.cc:735:  Lines should be <= 80 characters long  [whitespace/line_length] [2]
2021-02-10T02:56:29.7464144Z /github/workspace/src/systems/joint_trajectory_controller/JointTrajectoryController.cc:742:  Lines should be <= 80 characters long  [whitespace/line_length] [2]
2021-02-10T02:56:29.7465815Z /github/workspace/src/systems/joint_trajectory_controller/JointTrajectoryController.cc:803:  Lines should be <= 80 characters long  [whitespace/line_length] [2]
2021-02-10T02:56:29.7467461Z /github/workspace/src/systems/joint_trajectory_controller/JointTrajectoryController.cc:824:  Lines should be <= 80 characters long  [whitespace/line_length] [2]
2021-02-10T02:56:29.7469126Z /github/workspace/src/systems/joint_trajectory_controller/JointTrajectoryController.cc:846:  Lines should be <= 80 characters long  [whitespace/line_length] [2]
2021-02-10T02:56:29.7470790Z /github/workspace/src/systems/joint_trajectory_controller/JointTrajectoryController.cc:872:  Lines should be <= 80 characters long  [whitespace/line_length] [2]
2021-02-10T02:56:29.7472438Z /github/workspace/src/systems/joint_trajectory_controller/JointTrajectoryController.cc:873:  Lines should be <= 80 characters long  [whitespace/line_length] [2]
2021-02-10T02:56:29.7474106Z /github/workspace/src/systems/joint_trajectory_controller/JointTrajectoryController.cc:879:  Lines should be <= 80 characters long  [whitespace/line_length] [2]
2021-02-10T02:56:29.7475766Z /github/workspace/src/systems/joint_trajectory_controller/JointTrajectoryController.cc:884:  Lines should be <= 80 characters long  [whitespace/line_length] [2]
2021-02-10T02:56:29.7477427Z /github/workspace/src/systems/joint_trajectory_controller/JointTrajectoryController.cc:892:  Lines should be <= 80 characters long  [whitespace/line_length] [2]
2021-02-10T02:56:29.7479079Z /github/workspace/src/systems/joint_trajectory_controller/JointTrajectoryController.cc:917:  Lines should be <= 80 characters long  [whitespace/line_length] [2]
2021-02-10T02:56:29.7480737Z /github/workspace/src/systems/joint_trajectory_controller/JointTrajectoryController.cc:924:  Lines should be <= 80 characters long  [whitespace/line_length] [2]
2021-02-10T02:56:29.7483303Z /github/workspace/src/systems/joint_trajectory_controller/JointTrajectoryController.cc:963:  Using C-style cast.  Use static_cast<float>(...) instead  [readability/casting] [4]
2021-02-10T02:56:29.7485046Z /github/workspace/src/systems/joint_trajectory_controller/JointTrajectoryController.cc:982:  Lines should be <= 80 characters long  [whitespace/line_length] [2]
2021-02-10T02:56:29.7486786Z /github/workspace/src/systems/joint_trajectory_controller/JointTrajectoryController.cc:664:  Add #include <map> for map<>  [build/include_what_you_use] [4]
2021-02-10T02:56:29.7488407Z /github/workspace/src/systems/joint_trajectory_controller/JointTrajectoryController.cc:735:  Add #include <memory> for shared_ptr<>  [build/include_what_you_use] [4]
2021-02-10T02:56:29.7490028Z /github/workspace/src/systems/joint_trajectory_controller/JointTrajectoryController.cc:736:  Add #include <string> for string  [build/include_what_you_use] [4]
2021-02-10T02:56:29.7491648Z /github/workspace/src/systems/joint_trajectory_controller/JointTrajectoryController.cc:755:  Add #include <vector> for vector<>  [build/include_what_you_use] [4]
2021-02-10T02:56:29.7493410Z /github/workspace/src/systems/joint_trajectory_controller/JointTrajectoryController.hh:158:  At least two spaces is best between code and comments  [whitespace/comments] [2]
2021-02-10T02:56:29.7495381Z /github/workspace/src/systems/joint_trajectory_controller/JointTrajectoryController.hh:159:  At least two spaces is best between code and comments  [whitespace/comments] [2]
2021-02-10T02:56:29.7497158Z /github/workspace/src/systems/joint_trajectory_controller/JointTrajectoryController.hh:160:  At least two spaces is best between code and comments  [whitespace/comments] [2]
2021-02-10T02:56:29.7498946Z /github/workspace/src/systems/joint_trajectory_controller/JointTrajectoryController.hh:161:  At least two spaces is best between code and comments  [whitespace/comments] [2]
2021-02-10T02:56:29.7500697Z /github/workspace/src/systems/joint_trajectory_controller/JointTrajectoryController.hh:156:  Add #include <memory> for unique_ptr<>  [build/include_what_you_use] [4]
2021-02-10T02:56:29.7502179Z /github/workspace/test/integration/joint_trajectory_controller_system.cc:56:  Lines should be <= 80 characters long  [whitespace/line_length] [2]
2021-02-10T02:56:29.7503515Z /github/workspace/test/integration/joint_trajectory_controller_system.cc:57:  Lines should be <= 80 characters long  [whitespace/line_length] [2]
2021-02-10T02:56:29.7504831Z /github/workspace/test/integration/joint_trajectory_controller_system.cc:70:  Lines should be <= 80 characters long  [whitespace/line_length] [2]
2021-02-10T02:56:29.7506168Z /github/workspace/test/integration/joint_trajectory_controller_system.cc:71:  Lines should be <= 80 characters long  [whitespace/line_length] [2]
2021-02-10T02:56:29.7508255Z /github/workspace/test/integration/joint_trajectory_controller_system.cc:108:  Do not use variable-length arrays.  Use an appropriately named ('k' followed by CamelCase) compile-time constant for the size.  [runtime/arrays] [1]
2021-02-10T02:56:29.7509920Z /github/workspace/test/integration/joint_trajectory_controller_system.cc:116:  Lines should be <= 80 characters long  [whitespace/line_length] [2]
2021-02-10T02:56:29.7511254Z /github/workspace/test/integration/joint_trajectory_controller_system.cc:130:  Lines should be <= 80 characters long  [whitespace/line_length] [2]
2021-02-10T02:56:29.7512592Z /github/workspace/test/integration/joint_trajectory_controller_system.cc:131:  Lines should be <= 80 characters long  [whitespace/line_length] [2]
2021-02-10T02:56:29.7513904Z /github/workspace/test/integration/joint_trajectory_controller_system.cc:185:  Lines should be <= 80 characters long  [whitespace/line_length] [2]
2021-02-10T02:56:29.7515354Z /github/workspace/test/integration/joint_trajectory_controller_system.cc:185:  Using deprecated casting style.  Use static_cast<float>(...) instead  [readability/casting] [4]
2021-02-10T02:56:29.7516762Z /github/workspace/test/integration/joint_trajectory_controller_system.cc:198:  Lines should be <= 80 characters long  [whitespace/line_length] [2]
2021-02-10T02:56:29.7518974Z /github/workspace/test/integration/joint_trajectory_controller_system.cc:202:  Lines should be <= 80 characters long  [whitespace/line_length] [2]
2021-02-10T02:56:29.7529862Z /github/workspace/test/integration/joint_trajectory_controller_system.cc:203:  Lines should be <= 80 characters long  [whitespace/line_length] [2]
2021-02-10T02:56:29.7531236Z /github/workspace/test/integration/joint_trajectory_controller_system.cc:221:  Lines should be <= 80 characters long  [whitespace/line_length] [2]
2021-02-10T02:56:29.7532567Z /github/workspace/test/integration/joint_trajectory_controller_system.cc:222:  Lines should be <= 80 characters long  [whitespace/line_length] [2]
2021-02-10T02:56:29.7534187Z /github/workspace/test/integration/joint_trajectory_controller_system.cc:236:  Lines should be <= 80 characters long  [whitespace/line_length] [2]
2021-02-10T02:56:32.6029183Z /github/workspace/test/integration/joint_trajectory_controller_system.cc:268:  Do not use variable-length arrays.  Use an appropriately named ('k' followed by CamelCase) compile-time constant for the size.  [runtime/arrays] [1]
2021-02-10T02:56:32.6031172Z /github/workspace/test/integration/joint_trajectory_controller_system.cc:276:  Lines should be <= 80 characters long  [whitespace/line_length] [2]
2021-02-10T02:56:32.6032538Z /github/workspace/test/integration/joint_trajectory_controller_system.cc:290:  Lines should be <= 80 characters long  [whitespace/line_length] [2]
2021-02-10T02:56:32.6033854Z /github/workspace/test/integration/joint_trajectory_controller_system.cc:291:  Lines should be <= 80 characters long  [whitespace/line_length] [2]
2021-02-10T02:56:32.6035182Z /github/workspace/test/integration/joint_trajectory_controller_system.cc:345:  Lines should be <= 80 characters long  [whitespace/line_length] [2]
2021-02-10T02:56:32.6036590Z /github/workspace/test/integration/joint_trajectory_controller_system.cc:345:  Using deprecated casting style.  Use static_cast<float>(...) instead  [readability/casting] [4]
2021-02-10T02:56:32.6038016Z /github/workspace/test/integration/joint_trajectory_controller_system.cc:358:  Lines should be <= 80 characters long  [whitespace/line_length] [2]
2021-02-10T02:56:32.6039335Z /github/workspace/test/integration/joint_trajectory_controller_system.cc:362:  Lines should be <= 80 characters long  [whitespace/line_length] [2]
2021-02-10T02:56:32.6040657Z /github/workspace/test/integration/joint_trajectory_controller_system.cc:363:  Lines should be <= 80 characters long  [whitespace/line_length] [2]
2021-02-10T02:56:32.6041515Z Total errors found: 163

@AndrejOrsula
Copy link
Contributor Author

The code checker has several complaints

Sorry about that. They should all be corrected by e30cbb8 now.

@chapulina chapulina merged commit 14cc837 into gazebosim:ign-gazebo4 Feb 11, 2021
Core development automation moved this from In review to Done Feb 11, 2021
@j-rivero j-rivero removed this from Done in Core development May 6, 2022
Sign up for free to join this conversation on GitHub. Already have an account? Sign in to comment
Labels
🔮 dome Ignition Dome
Projects
None yet
Development

Successfully merging this pull request may close these issues.

None yet

2 participants