Skip to content

Conversation

@jacquelinekay
Copy link
Contributor

This pull request adds:

  • pendulum_control package
  • pendulum_msgs package for custom message types. (Originally I considered using sensor_msgs::JointState, but since it contains a string field, it is not a fixed size message.)
  • RttExecutor: an executor instrumented for collecting data for real-time performance statistics
  • pendulum_demo.cpp: provides a main function that intializes rclcpp, nodes, publishers/subscribers, and executor. Print output to screen in a separate, low-priority thread.
  • PendulumController: Store PID properties, provide the next command message based on the received sensor message.
  • PendulumMotor: Abstraction for the physical state of the pendulum system. Change the state based on the command message and provide the next sensor message. Runs a separate "physics update" thread to update the state of the pendulum.

The README.md file contains more information about how to configure your system to see "soft" real-time performance results.

@jacquelinekay jacquelinekay added the in progress Actively being worked on (Kanban column) label Aug 12, 2015
@jacquelinekay jacquelinekay self-assigned this Aug 12, 2015
Copy link
Member

Choose a reason for hiding this comment

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

Not listed in the manifest.

@jacquelinekay jacquelinekay force-pushed the realtime_demo branch 4 times, most recently from cb4805e to bf9bc92 Compare August 17, 2015 21:55
@jacquelinekay jacquelinekay changed the title Stub out realtime control demo Minimal implementation of realtime control demo Aug 17, 2015
@jacquelinekay jacquelinekay added in review Waiting for review (Kanban column) and removed in progress Actively being worked on (Kanban column) labels Aug 17, 2015

Choose a reason for hiding this comment

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

Use CLOCK_MONOTONIC instead, so physics aren't affected by system time changes (NTP slew, user calling date --set=Fri May 4 13:38:56 CEST 1979).

For relative-time, high-precision computations like sleeping, the monotonic source is to be preferred. CLOCK_REALTIME is best left for synchronizing events on an absolute time reference, like start pendulum stabilization tomorrow at 3pm.

@jacquelinekay jacquelinekay force-pushed the realtime_demo branch 2 times, most recently from 195dc63 to fa0f41b Compare August 19, 2015 20:58
@jacquelinekay
Copy link
Contributor Author

To enable CI for this demo, we need to add the dependency rttest to ros2.repos and clean up rttest for Jenkins:

ros2/examples/pull/49
ros2/realtime_support/pull/2

edit: done

@jacquelinekay
Copy link
Contributor Author

I changed the CMakeLists to avoid building this package on OSX and Windows and started CI:

http://ci.ros2.org/job/ros2_batch_ci_linux/251/
http://ci.ros2.org/job/ros2_batch_ci_osx/179/
http://ci.ros2.org/job/ros2_batch_ci_windows/258/
http://ci.ros2.org/job/ros2_batch_ci_windows/259/ (WIN32, not WIN_32...)

We should expect Linux to build the package cleanly and OSX and Windows to avoid building it (though they will install a dummy "pendulum_control" package, since I don't know how to tell ament to avoid installing the package).

@dirk-thomas
Copy link
Member

If you don't call ament_package it won't install anything. Not sure if that generates any issues down the road though.

@jacquelinekay
Copy link
Contributor Author

ah, I understand my issue now...

If I returned from the package without calling find_package(ament_cmake)
beforehand, ament would try to install the package and complain about no
install rule:

+++ Installing 'pendulum_control'
==> '. /home/jackie/code/ros2_ws/build/pendulum_control/cmake__install.sh
&& /usr/bin/make install' in
'/home/jackie/code/ros2_ws/build/pendulum_control'
make: *** No rule to make target `install'.  Stop.

William suggested I add ament_package as a workaround, but it I just find
ament before checking the OS flags, it returns without throwing an error or installing
the package.

@dirk-thomas
Copy link
Member

If not having any install steps is a viable use case we could make ament_tools skip the install step in that case.

@jacquelinekay
Copy link
Contributor Author

well, looks like calling return() after find_package(ament_cmake) but before ament_package() still doesn't work on Jenkins:

http://ci.ros2.org/job/ros2_batch_ci_osx/180/
http://ci.ros2.org/job/ros2_batch_ci_windows/260/

Is there a recommended way to conditionally skip the installation of a package?

@dirk-thomas
Copy link
Member

If a package does not use install() anywhere it won't have an install target. Currently ament_tools always invokes make install. Either we have to update the tool to check if the target exists and only then invoke it or the package must install something. I can make a PR for ament_tools if we think it is viable to not have an install package.

@wjwwood
Copy link
Member

wjwwood commented Aug 21, 2015

I agree that the build tool should not fail if a package has no install target, but calling ament_package() should have created one in order to install the package.xml?

@jacquelinekay
Copy link
Contributor Author

@wjwwood The failed build happened after I took out the ament_package workaround, I thought simply calling find_package(ament_cmake) before returning would work but it did not.

I think it is viable to allow for conditionally not installing a package, unless we want to discourage people from making code that only compiles on one OS.

The situation here is that rttest only compiles on Linux, so for OSX and Windows, an empty package is installed. This means that I have to repeat the conditional if(APPLE OR WIN_32) here to avoid attempting to compile on OSX and Windows, instead of skipping if rttest was not installed. For cases where conditionally building a package is more complicated, repeating the condition could be very unwieldy.

@tfoote
Copy link
Contributor

tfoote commented Aug 21, 2015

Overall this looks good to me. +1 pending the CI issues resolution.

Copy link
Member

Choose a reason for hiding this comment

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

If you move the find_package() call below the platform check it will exit a bit fast on non Linux system.

@dirk-thomas
Copy link
Member

+1 (beside nit picking).

@jacquelinekay
Copy link
Contributor Author

jacquelinekay added a commit that referenced this pull request Aug 22, 2015
Minimal implementation of realtime control demo
@jacquelinekay jacquelinekay merged commit 19e5bbe into master Aug 22, 2015
@jacquelinekay jacquelinekay removed the in review Waiting for review (Kanban column) label Aug 22, 2015
@jacquelinekay jacquelinekay deleted the realtime_demo branch August 22, 2015 01:40
Sign up for free to join this conversation on GitHub. Already have an account? Sign in to comment

Labels

None yet

Projects

None yet

Development

Successfully merging this pull request may close these issues.

6 participants