diff --git a/debian/changelog b/debian/changelog new file mode 100644 index 0000000..164f9a2 --- /dev/null +++ b/debian/changelog @@ -0,0 +1,1288 @@ +ros-humble-naoqi-driver (2.1.1-1bullseye) bullseye; urgency=high + + * Drop testing of foxy and galactic + * README: remove extraneous args in example + * Update code and instructions about Docker + * Fix build for humble + * Improve README about audio service + * Contributors: Victor Paléologue + + -- Victor Paléologue Mon, 04 Dec 2023 23:00:00 -0000 + +ros-humble-naoqi-driver (2.1.0-1bullseye) bullseye; urgency=high + + * New "Listen" action + * Remove usages of BOOST_FOREACH + * New qi_listen_url option and update README + * Track ros2 branch of nao_meshes + * Get odom at the same time as joint states + * No need to register the driver as a NAOqi service + * Simplify starting and stopping the node + An extra thread is not required anymore to run the ROS loop. + * Safer unsubscription from ALMemory + * Switch to NAOqi 2 subscribers for touch events + * Fix build warnings + * libqi-related warningsUse .value() when getting a Qi service + + * Fix lack of return value in camera.cpp + * Fix deprecated include to image_transport.h + * Remove unused mentions to behavior trees + + * Better error messages + * Transform computation + * Experimental running the driver and for dev + Adapted from https://github.com/sea-bass/turtlebot3_behavior_demos + * Support NAOqi 2.8 (NAO v6) + * Repair audio + * Support for humble & iron + * RViz files converted to RViz2 ones + * Update use of placeholders + * Update robot description code + * Remove mentions to catkin + * Update README: + * New details about building meshes + * How to build from source now + * Remove dependence to orocos-kdl + * Contributors: Maxime Busy, Victor Paleologue, Victor Paléologue + + -- Victor Paléologue Wed, 22 Nov 2023 23:00:00 -0000 + +ros-humble-naoqi-driver (2.0.0-1bullseye) bullseye; urgency=high + + * Update README, add buildfarm status badges + * Fix typos in README, update username arg in launchfile + * Merge branch 'ros2_integration' into main + * Remove old README + * Migrate Travis CI to github actions, remove spurious README + * Update the package version, add a README.md + * Initial commit + * Fix robot_state_publisher header import + * Merge branch 'naoqi-2.9' into ros2_integration + * Merge branch 'temp_tests' into naoqi-2.9 + * Correct include towards ros_helper, and small functional updates + * Refactor the converters for NAOqi 2.9 compatibility + * Refactor the audio event for NAOqi 2.9 compatibility + * Add the NaoqiVersion struct + * Add the getNaoqiVersion and isNaoqiVersionLesser methods, refactor the getInfoRobotLocal method + * Update the package definition and its CMakeLists + * Fix the Driver class + * Fix the subscribers + * Fix the services + * Fix the recorders + * Fix the publishers + * Fix the helpers + * Fix the events + * Fix the converters + * Fix project headers + * Merge pull request #10 from arturocuma/subscriber_refactoring + Subscriber refactoring + * Merge pull request #9 from mcaniot/publishers_refactoring + Publishers refactoring + * Merge pull request #8 from elagrue/event_refactoring + Event refactoring + * Merge pull request #7 from mbusy/converters_refactoring + Converters refactoring + * Merge pull request #6 from mbusy/migration_helpers + Migration helpers + * Merge pull request #5 from mbusy/driver_refactoring + Driver refactoring + * Merge pull request #4 from mbusy/services_refactoring + Services refactoring + * Merge pull request #3 from mbusy/helpers_refactoring + Helpers refactoring + * Merge pull request #2 from mbusy/recorders_refactoring + Recorders refactoring + * Merge pull request #1 from mbusy/interface_headers + Interface headers + * adding const at speech_callback + * changing ConstSharedPtr to ConstSharedPtr& + * pull request changes + * refactor teleop subscriber for geometry_msgs, naoqi_bridge_msgs compliancy + * refactor speech subscriber for rclcpp, std_msgs compliancy + * refactor moveto for rclcpp, geometry_msgs compliancy + * Fix Refactor sonar publisher + replace it by (*it) + * Fix Refactor camera publisher + replace create_publisher by create_camera_publisher + * Event refactoring minor bugfix + * Fix Refactor sonar publisher + replace Publisher with Publisher::SharedPtr + replace publishers::getNumSubscribers by Node::count_subscribers + use clear() function to reset vector pubs_ + replace . by -> + * Fix Refactor log publisher + remove header serialization.h + replace Publisher by Publisher::SharedPtr + * Fix helpers called function + replace getNumSubscribers by count_subscribers + * Fix Refactor joint_state publisher + replace rclcpp::Publisher by rclcpp::Publisher::SharedPtr + replace . by -> + * Fix Refactor Info + remove unnecessary parameters + replace StringStamped by string_stamped + * Fix Refactor Camera publisher + Add note above commented code + remove unused header + replace helpers::pulishers by helpers::Node + * Fix Refactor basic publisher + replace rclcpp::Publisher by rclcpp::Publisher::SharedPtr + * Fix Refactor basic publisher + replace helpers::publishers by helper::Node + * Specify the IP address when calling the stopRecord method in the Driver class + * Remove the Master URI related methods in ros_env.hpp + * Fix include names for the driver_helpers header + * Global fix for the services + * Fix the converter accoring to the review of PR #7 + * Refactor Camera publisher + add msg namespace + replace ros::NodeHandle by rclcpp::Node + replace . by pointer -> + replace ros by rclcpp + add helpers to replace deprecaded getNumSubscribers + comment if that remove compressedDepth topics check if still poping in ros2 + * Refactor the touch event + * Refactor the basic event + * Refactor the audio event + * Refactor the touch converter + * Refactor the sonar converter + * Refactor the odom converter + * Refactor the nao footprint header + * Refactor info publisher + add msg namespace + replace ros::NodeHandle by rclcpp::Node + replace . by pointer -> + replace ros by rclcpp + replace setParam by set_parameters + * Refactor the memory list converter + * Refactor sonar publisher + add msg namespace + replace ros::NodeHandle by rclcpp::Node + replace . by pointer -> + replace advertise by create_publisher + replace ros by rclcpp + add helpers to replace getNumSubscribers + * Refactor log publisher + replace ros bu rclcpp + replace rosgraph_msgs by rcl_interfaces/msg + * Refactor the joint_state publisher + add msg namespace + replace ros::NodeHandle by rclcpp::Node + replace . by pointer -> + replace advertise by create_publisher + replace ros by rclcpp + * Refactor the basic publisher + add msg namespace + replace ros::NodeHandle by rclcpp::Node + replace . by pointer -> + replace advertise by create_publisher + replace ros by rclcpp + add helpers function to replace getNumSubscribers + * Refactor the log converter. Use rcl_interfaces::msg::Log and the RCUTILS_LOG_SEVERITY enum + * Remove unnecessary classes, realocate the various methods in the Node class. The Time class is kept for now, but ought to be removed in the future + * Add the Logger helper class, allowing to access to the driver node's logger throughout the project + * Add the Publisher helper class, rendering Publisher related features accessible throughout the project + * Add a node helper class to set the shared ptr towards the node, refactor the external registration script accordingly + * Refactor the laser converter + * Refactor the joint state converter. The general rclcpp logger is used to log, that might be modified in the future + * Refactor the info converter + * Refactor the imu converter + * Refactor the diagnostics converter + * Refactor memory publisher: correct headers names + namespace with _ + replace .h missing by .hpp + * Refactor the camera converter. Logging with the rclcpp general logger might be a problem + * Refactor the string memory publisher + add msg namespace + replace ros::NodeHandle by rclcpp::Node + replace . by pointer -> + replace advertise by create_publisher + * Refactor the int memory publisher + add msg namespace + replace ros::NodeHandle by rclcpp::Node + replace . by pointer -> + replace advertise by create_publisher + * Refactor the float memory publisher + add msg namespace + replace ros::NodeHandle by rclcpp::Node + replace . by pointer -> + replace advertise by create_publisher + * Refactor the bool memory publisher + add msg namespace + replace ros::NodeHandle by rclcpp::Node + replace . by pointer -> + replace advertise by create_publisher + * Refactor the camera info definitions header + * Refactor the audio converter + * Use StringStamped.hpp in the string memory converter + * Refactor the string memory converter + * Refactor the int memory converter + * Refactor the float memory converter + * Refactor the bool memory converter + * Set the qi session of the driver in the external registration script + * Refactor the driver class + * Refactor the set_language service + * Refactor the robot_config service + * Include the GetString hpp header in the get_language service + * Refactor the get_language service + * Refactor the driver_helpers, handle the new syntax for the naoqi_bridge_custom messages + * Refactor the filesystem_helpers, use ament_index_cpp to get the packages share directories + * Refactor transform_helpers, update the includes and the ROS message types + * Refactor the global recorder to use the method of the recorder helper + * Use the method provided by the recorder helper to check if the message timestamps are set to 0 + * Add the isZero static method to the recorder helper + * Refactor the sonar recorder + * refactor the log recorder + * Refactor the joint_state recorder + * Refactor the diagnostics recorder + * Refactor the camera recorder + * Refactor the basic recorder + * Refactor the basic_event recorder + * Use the time helper to call now() + * Refactor the globalrecorder recorder. For now the rosbag2 calls are commented + * Refactor the event interface header for rclcpp compliance + * Refactor recorder interface header. The rosbag includes will have to be updated + * Refactor the service interface header for rclcpp compliance + * Refactor the subscriber interface header for rclcpp compliance + * Refactor converter interface header for rclcpp compliance + ros::Node::now() might not work, to be possibly updated + * Refactor the publisher interface header for rclcpp compliance + * Relocalize the Time helper in the includes folder + * Initialize the time helper in the external registration, and add comments + * Update CMakeLists for the whole project + * Add a time helper for the project + * Update the external registration code for rclcpp compliance + * Add the DriverAuthenticator and DriverAuthenticatorFactory classes + * Add a python launchfile for ros2 launch + * Use only one CMakeLists for colcon build + * Update package.xml for ros2 compatibility + * Removing unused naoqi_env file + * Merge pull request #132 from mbusy/robust_movebase + Robustify moveTo + * Safer moveTo: only odom and base_footprint are accepted as references, and check if yaw is nan + * Merge pull request #131 from ros-naoqi/testing_repo + Update CI for melodic + * melodic not allowed to fail anymore, indigo allowed + * use testing repo + * Contributors: Arturo, Arturo Cruz, Edo, Maxime Busy, Mikael Arguedas, Pandhariix, eneuron, mbusy, mcaniot + + -- Victor Paléologue Mon, 12 Sep 2022 22:00:00 -0000 + +ros-humble-naoqi-driver (0.5.11-1bullseye) bullseye; urgency=high + + * Merge pull request #129 from Pandhariix/melodic_compatibility + Melodic compatibility + * Merge pull request #126 from Pandhariix/lasers_range + Parametrizable range for Pepper's lasers + * Merge pull request #130 from Pandhariix/melodic_ci + Adapt the README to the new CI + * Update CI, add melodic-stretch + * Adapt the README to the new CI + * Merge pull request #128 from ros-naoqi/use_ici + use industrial_ci instead of custom CI + * send emails only for builds on master branch + Signed-off-by: Mikael Arguedas + * use industrial_ci instead of custom CI + Signed-off-by: Mikael Arguedas + * Remove -Werror=deprecated-declarations to compile for melodic + * Replace the joint and joint mimics boost shared pointers by urdf::JointMimicSharedPtr & urdf::JointSharedPtr + * Include iostream to avoid cout not a member of std + * Merge pull request #127 from ros-naoqi/remove_eol_lunar + remove EOL ROS Lunar from travis config + * remove lunar from readme as well + Signed-off-by: Mikael Arguedas + * remove EOL ROS Lunar from travis config + Signed-off-by: Mikael Arguedas + * Parametrizable range for Pepper's lasers. Default range, 0.1 to 3.0 meters + * Merge pull request #125 from Pandhariix/indigo_ci + Use std::numeric_limits::quiet_NaN for indigo compatibility + * Merge pull request #124 from ros-naoqi/fix_orocos + upgrade to make sure all package versions are consistent + * Replace std::nan to std::numeric_limits::quiet_NaN for the indigo compatibility + * upgrade to make sure all package versions are comsistent + Signed-off-by: Mikael Arguedas + * Merge pull request #123 from ros-naoqi/rosdep_eol + pass rosdep eol flag + * pass rosdep eol flag + Signed-off-by: Mikael Arguedas + * Merge pull request #113 from Pandhariix/master + Add velocities and torques to the joint states + * Changing the maintainer + * Add velocities and torques to the joint states + * Merge pull request #112 from Pandhariix/hotfix/indigo_compilation + Fix compilation error for indigo + * Fix compilation error for indigo + * Merge pull request #111 from Pandhariix/feature/stereo + Feature/stereo + * Print the detected version of the robot + * Update boot_config to take into account the stereo + * Update naoqi_driver to take into account robots with stereo + * Add methods handling the camera parameters for the stereo cameras and call them in the getCameraInfo method + * Update the CameraConverter class to take the stereo into account + * Add the isDepthStereo method to the driver helpers + * Add the RGB Stereo and Depth Stereo parameters to the vision definitions + * Merge pull request #108 from kochigami/add-initializing-message + * add naoqi_driver initialized message + * modify the message of service and subscriber registering process + * modify message of service and subscriber registering process like others + * add naoqi_driver initialized message + * Contributors: Kanae Kochigami, Maxime Busy, Mikael Arguedas, Natalia Lyubova, Pandhariix, Séverin Lemaignan + + -- Victor Paléologue Tue, 07 Jan 2020 23:00:00 -0000 + +ros-humble-naoqi-driver (0.5.10-1bullseye) bullseye; urgency=high + + * disable logs as default (reference #68 ) (#88 ) + * Missing tf2 include and tf2 exception type (#103 ) + * Add missing include tf2_ros/buffer.h + * Catch tf2::TransformException + * add services for get and set language (#87 ) + * C-style comments are not syntactically correct in JSON (#98 ) + * C-style comments are not syntactically correct in JSON + * Remove Jade from Travis description (#95 ) + * Remove Jade from Travis description and CI matrix + * Correct badges according to the Travis matrix modification, and add Debian stretch badge + * Adding a maintainer + * Ci (#94 ) + * Add .travis.yml + * Adding a warning for VGA resolution for depth camera (#93 ) + Adding a warning for VGA resolution for depth camera + * Merge pull request #92 from Pandhariix/add_joint_limits + Add joint limits to the diagnostics + * Start adding joints limits to the diagnostic + Add double layered float vector converter method + Add the joints limit map, and add the joints limits to the diagnostic message + * Update gitignore + * Fix typo in naoqi_driver.hpp + * Merge pull request #85 from PacoDu/fix_node_name_empty + Fix node name empty related to pepper_robot issue #35 + * Update naoqi_driver.cpp + Error while merging, setPrefix removed. + * Fix node name issue #35 + * Contributors: Dupont Paco, Esteve Fernandez, Kanae Kochigami, Maxime Busy, Natalia Lyubova, Paco Dupont, Shane Loretz, Surya Ambrose + + -- Victor Paléologue Thu, 15 Feb 2018 23:00:00 -0000 + +ros-humble-naoqi-driver (0.5.9-1bullseye) bullseye; urgency=high + + * -Vincent Rabaud as a maintainer, +Natalia Lyubova + * Merge pull request #75 from kochigami/rename-tactile-touch-to-head-touch + rename tactile touch to head touch + * rename boot_config name of hand & head + * rename tactile touch to head touch + * Merge pull request #63 from kochigami/add-hand-touch-sensor-input-to-touch-programs + Add hand touch sensor input to touch event and converters + * add hand touch sensor input to touch programs + * Merge pull request #74 from kochigami/try-depth-raw + kRawDepthColorSpace for depth image + * Merge pull request #36 from laurent-george/adding_odom_frame + Adding odom topic to the bridge + * fix(odom): update code based on comment in pull request + * Adding odom topic to the bridge + * Merge pull request #72 from furushchev/increase-joint-state-freq + [share/boot_config.json] increase frequency for publishing joint_states + * [share/boot_config.json] increase frequency for publishing joint_states + * Update package.xml + * kRawDepthColorSpace for depth image + * Contributors: Kanae Kochigami, Karsten Knese, Laurent GEORGE, Mikael Arguedas, Natalia Lyubova, Vincent Rabaud, Yuki Furuta, lgeorge + + -- Victor Paléologue Mon, 07 Nov 2016 23:00:00 -0000 + +ros-humble-naoqi-driver (0.5.8-1bullseye) bullseye; urgency=high + + * Update maintainership + * Fix broken compilation with libqi-2.5 (#67 ) + -std=gnu++11 is not mandatory as this flag will be added when importing libqi + (https://github.com/ros-naoqi/libqi-release/commit/c26f57e25326c9d3447ae7113818a474994e5544). + naoqi_driver should now work with libqi2.3 and 2.5 + * Contributors: Surya Ambrose + + -- Victor Paléologue Wed, 18 May 2016 22:00:00 -0000 + +ros-humble-naoqi-driver (0.5.7-1bullseye) bullseye; urgency=high + + * Fix termination issues (#62 ) + + * Fix deadlock in audio termination + Calling subscribe or unsubscribe while the callback is being called + is already protected on naoqi side. So no need to protect it on the bridge + side, this is what previously led to a deadlock. + We only need mutex protection on configuration variable (publishing, + recording, logging) and also make sure calling subscribe and unsubscribe + at the same time is not possible (even though this is also protected in + naoqi). + Change-Id: Iae604c047046fec9e24832dd4df5017ff4ae724f + * Do not use qi::import for retrieving naoqi_driver + Change-Id: I1443ce10576f10ceda5041139c90a3df2e65f043 + * unsubscribe each events + * Fix stopService being called twice + * Do not create info converter if not necessary + * Fix segfault on termination + + * #58 is not compatible with previous version... (#60 ) + * Add tactile and bumper in boot_config.json (#59 ) + * fix when no name space is found (#58 ) + * use template for TouchEventRegister + * use template class(TouchEventConverter) in conveerters/touch.{cpp,hpp} + * add touch event and converters + * Contributors: Kei Okada, Surya Ambrose, Vincent Rabaud + + -- Victor Paléologue Wed, 03 Feb 2016 23:00:00 -0000 + +ros-humble-naoqi-driver (0.5.6-1bullseye) bullseye; urgency=high + + * register audio_enabled only when audio is set enabled + * launch/naoqi_driver.launch : support nao_port + * fixing body temperature for Romeo + * missing romeo.urdf + * update to the latest URDF + * call startPublishing instaed of set true to publish_enabled_ + * update to the latest urdf + * add subscribers/speech.cpp + * converters/joint_state.cpp: support mimic joint tf publisher + * Contributors: Karsten Knese, Kei Okada, Surya Ambrose, Vincent Rabaud, nlyubova + + -- Victor Paléologue Sat, 26 Dec 2015 23:00:00 -0000 + +ros-humble-naoqi-driver (0.5.5-1bullseye) bullseye; urgency=high + + * fix correct loading of urdf + * Contributors: Karsten Knese + + -- Victor Paléologue Wed, 26 Aug 2015 22:00:00 -0000 + +ros-humble-naoqi-driver (0.5.4-1bullseye) bullseye; urgency=high + + * remove useless include + * add V Rabaud as a maintainer + * Contributors: Vincent Rabaud + + -- Victor Paléologue Wed, 26 Aug 2015 22:00:00 -0000 + +ros-humble-naoqi-driver (0.5.3-1bullseye) bullseye; urgency=high + + * fix: advertise service in global ns + * Contributors: Karsten Knese + + -- Victor Paléologue Tue, 25 Aug 2015 22:00:00 -0000 + +ros-humble-naoqi-driver (0.5.2-1bullseye) bullseye; urgency=high + + * build and run dependency v004 for bridge msgs + * fill robot config data + * implement robot config service call + * change to latest robotinfo msg + * add sessionptr to service + * fill the service to get the robot info + * Merge pull request #38 from antegallya/patch-1 + Fix repo url in install.rst + * Fix repo url in install.rst + * Merge pull request #37 from antegallya/patch-1 + Fix a code-block in install.rst + * Fix a code-block in install.rst + * rename service topic to ros standard + * add license declaration + * add support for ros services + * update doc + * enhance error message in camera converter + * naoqi_driver_node is an executable not a library + * Contributors: Karsten Knese, Pierre Hauweele, Vincent Rabaud + + -- Victor Paléologue Tue, 25 Aug 2015 22:00:00 -0000 + +ros-humble-naoqi-driver (0.5.1-1bullseye) bullseye; urgency=high + + * rename dump_enabled to log_enabled + * introduce prefix to naoqi driver c'tor + * switch to boost program options + * do not set the log level if it has not changed + * get a more generic way of setting the log level + * publish to diagnostics as it should be + * respect the ROS log level + * cleanup main + * update rviz configuration + * extend teleop for set_angles + * exclude driver helper to cpp for one-call only + * cleanup battery diagnostics + * remove max velocity + * Merge pull request #30 from laurent-george/patch-1 + fix git repo url + * fix git repo url + it's a _ not a - + * change doc for renaming to naoqi driver + * renamed files for naoqi_driver + * update doc to correct renaming + * update doc to correct renaming + * add stiffness and fix battery status + * Contributors: George Laurent, Karsten Knese, Vincent Rabaud + * remove legacy code + * fix typo in package.xml + * rename package to naoqi_driver + * remove alrosbridge prefix and cleanup + * fix typo in cmakelist + * Fixes for c++11 + * remove naoqi_msgs includes + * fix for correct header include of msgs + * remove deprecation warning + * Contributors: Guillaume JACOB, Karsten Knese, Vincent Rabaud + + -- Victor Paléologue Mon, 10 Aug 2015 22:00:00 -0000 + +ros-humble-naoqi-driver (0.1.2-1bullseye) bullseye; urgency=high + + * update start doc for v1.2 + * lower default values for camera + * add bottom camera + * create launch file for running rosbridge + * remove ros args from cmdline + * nao basefootprint + * remove ros args + * main: support 2nd argument as network interface + * ros_env.hpp write error message when network interface is not found + * include install instructions for ROS + * Contributors: Karsten Knese, Kei Okada, Vincent Rabaud + + -- Victor Paléologue Tue, 14 Jul 2015 22:00:00 -0000 + +ros-humble-naoqi-driver (0.1.1-1bullseye) bullseye; urgency=high + + * update the Pepper URDF + * add optical frame + * Contributors: Karsten Knese, Vincent Rabaud + + -- Victor Paléologue Wed, 24 Jun 2015 22:00:00 -0000 + +ros-humble-naoqi-driver (0.1.0-1bullseye) bullseye; urgency=high + + * devel-space compatibility + * move application files to app folder + * Add methods to remove bags presents on folder + * Add an helper function to check size taken by bags + * Add an helper function to check presents bags on folder + * rename urdf + * add romeo.urdf + * update and rename files to be consistent with description + * update doc for rosrun + * updated roscore option in doc + * remove test folder + * Contributors: Karsten Knese, Marine CHAMOUX, Vincent Rabaud + + -- Victor Paléologue Wed, 17 Jun 2015 22:00:00 -0000 + +ros-humble-naoqi-driver (0.0.7-1bullseye) bullseye; urgency=high + + * correct filepath lookup for catkin and qibuild + * hotfix: do not cast 'getenv' return to string when it's null + * hotfix: allow to register correctly a converter on the fly + * Contributors: Karsten Knese, Marine CHAMOUX, zygopter + + -- Victor Paléologue Mon, 01 Jun 2015 22:00:00 -0000 + +ros-humble-naoqi-driver (0.0.6-1bullseye) bullseye; urgency=high + + * add install rule for the module file + * Contributors: Vincent Rabaud + + -- Victor Paléologue Wed, 27 May 2015 22:00:00 -0000 + +ros-humble-naoqi-driver (0.0.5-1bullseye) bullseye; urgency=high + + * clean seperation between catkin and qibuild + * adjust sdk prefixes with cmake_prefix + * fix devel problems and rename lib + * set sdk prefix to devel space + * add a file to register a NAOqi module + * Contributors: Karsten Knese, Vincent Rabaud + + -- Victor Paléologue Sat, 23 May 2015 22:00:00 -0000 + +ros-humble-naoqi-driver (0.0.4-1bullseye) bullseye; urgency=high + + * get code to compile with catkin + * Contributors: Vincent Rabaud + + -- Victor Paléologue Sun, 17 May 2015 20:48:00 -0000 + +ros-humble-naoqi-driver (0.0.3-1bullseye) bullseye; urgency=high + + * get code to compile with catkin + * Contributors: Vincent Rabaud + + -- Victor Paléologue Sun, 17 May 2015 19:22:00 -0000 + +ros-humble-naoqi-driver (0.0.2-1bullseye) bullseye; urgency=high + + * bump version + * get code to compile with catkin + * bugfix: cyclic buffer for log + * bugfix: apply config file + * replace tf helpers with tf2 + * remove legacy code + * introduce a config json format for configuring converters + * Merge pull request #7 from zygopter/master + Bufferize & minidump event converters (as audio) + * Hotfix: Put throwing function inside the try/catch + * Hotfix: use set_capacity instead of resize for circular buffer + * Hotfix: allow to record event converters in 'startRecordingConverters' + * Hotfix: put checker condition to true when record is started + * Better synchronazation of data for minidump + * Use a circular buffer instead of a simple list for optimization + * Add beggining time of minidump call for event synchronization + * Hotfix: block buffer writing to have synchronized data in minidump + * Hotfix: resize correctly the buffer when changing the duration + * Remove spamming logs + * Hotfix: set buffer duration for event converters + * Add prefix name for ROSBag in minidump + * Be able to write the event converter's buffer in miniDump + * Be able to bufferize event converters + * remove while loop in startConverter&miniDump + * Merge branch 'devel' (early part) + Conflicts: + src/alrosbridge.cpp + * introduce time lapse measure + * configuration booleans for default pub + * try lock for write_mutex + * Merge pull request #6 from zygopter/master + Correct Buffersize calculation + * Use a static const variable instead of a #define + * Add a getter method for buffer duration + * Set a global variable for default buffer duration + * Hotfix: set correct size for buffer + * Allow to start the application automatically + * Merge pull request #5 from zygopter/master + hotfix: bad path for header in test + * hotfix: bad path for header in test + * Merge pull request #4 from zygopter/master + Refactoring of audio converter to manage publishing & recording + * Merge pull request #3 from GuillaumeJacob/master + fix cameraInfo for infrared camera + * Refactor audio converter to manage to record it + * Rename event class and move to event folder + Delete unused files + * Split reset function into publisher & recorder for events + * fix cameraInfo for infrared camera + * Merge pull request #2 from Karsten1987/master + no roscore dependency for recording + * Merge pull request #1 from zygopter/master + Update documentation for installation + * Change 'git clone' by 'qisrc add' to download & reference projects in qibuild + * hotfix: setting timestamp + * trigger init function also with given roscore ip + * api change: start rosloop without rosmaster initialization + * exclude TransformBroadcaster into a shared_ptr + this allows to create a joint state publisher without a need to create a + nodehandle + * Add missing dependency in install.rst + * take rostime.now for camera to sync with other publisher + * Fix wrong project name in rst configuration file + * Add gitignore file + * remove console bridge dependency + * Initial commit + * Add link from rst doc to doxygen doc + * Update Doxyfile + * README points to the doc URL + * Use RST instead of markdown + * Doc test + * add support for Doxygen + * add instructions on how to build the docs + * fix: correct licence agreement + * adjust camera msg timestamp to alimage timestamp + * change colorspace to rgb8 for front camera + * Merge branch 'master' into 'master' + Master + * add color for better understanding + * bugfix on run script for linux64 + * Add dependency for linux64 + * Add qicli call function to choose converters for minidump + * Change message output for minidump and stop record + * support for IR camera + * hotfix: stabilize publisher frequence + * give the master ip directly via commandline args + * Fix doc line + * Prepare files for doxygen documentation + * Move test includes into test/ (so they are not considered by doxygen) + * Merge branch 'master' into 'master' + Master + * Factorize the code to retrieve anyvalues + * Hotfix: register callback to bufferize for memory converters + * Add test for minidump + * Add a setter function to choose the ROSbag duration for minidump + * Merge branch 'doc' into 'master' + Doc + * Merge branch 'master' into 'master' + Master + * Hotfix: catch exception when key does not exist in ALMemory && return boolean + * Doc fix + * Add links to go back to main menu + * Final touch + * Add topics page + * Add troubleshooting, next step and other usage pages + * Fix wrong definition of getMasterURI in api.rst + * Small fixes + * Add API page + * Add getting started page + * Create the index, add the howto install page + * Simplify README.rst, and point to the doc/ folder + * Avoid segfault if a value retrieval fails + * Merge branch 'compilation_fix' into 'master' + Compilation fix + * Fix compilation issue after toolchain update + * Merge branch 'mc/event' into 'master' + Mc/event + * Move 'getDataType' function to helpers.hpp + * Support no usage of ALValue + * support new recorder API + * remove useless debbug logs + * Switch in respect to data type of event + * Improve life functionement of event registration + * Refactor test due to library changes + * Check if the process is started + * Add a qicli function to register a memory converter + * Add mutexes in EventRegister + * Add a generic virtual class for event converter + * Add privacy to internal functions && delete test function + * Add test for new event ros bridge + * New class to deal with memory events + * Merge branch 'mc/devel' into 'master' + Mc/devel + * Use optional custom frequency for buffer data + * Fix test + * Add qicli call function to write a ROSbag with the last 10s data buffer + * Register LOG callback to 'bufferize' recorder's function + * recorder: Add function to write buffer in a ROSbag + * recorder: Add bufferize function for camera & new buffer frequency argument in constructor + * recorder: Add a function to bufferize converter's data over the last 10 sec + * recorder: Add frequency argument in recorder reset function + * recorder: Check if vector is empty before writing a TF message on ROSbag + * recorder: Check message timestamp to write it on ROSbag + * Change message type for Info converter + * unixify the README file + * Get rid of the qimessaging warning + * Update alvisiondefinitions.h with latest available doc (this fix #31 ) + * Remove useless comment + * Add security when getting image (in case no image is retrieved) + * Merge branch 'sa/no_alvalue' into 'master' + Sa/no alvalue + * Remove undesirable dependency + * Do not use ALValue when guessing memory key type anymore + * Do not use ALValue when retrieving memory list anymore + * Fix indexing error + * Do not use ALValue when retrieving audio anymore + * Do not use ALValue anymore to retrieve the cameras + * Merge branch 'mc/devel' into 'master' + Mc/devel + * recorder: be consistent between publisher topic & recorder topic + * Remove useless files (issue #28 ) + * remove alvalue includes + * use proper string conversion + * Fix #29 : wrong rviz config for nao + * Merge branch 'sa/devel' into 'master' + Sa/devel + * Audio converter (never stops) + * Merge branch 'mc/devel' into 'master' + Mc/devel + * Update README + * Add timestamp in memory list message + * Update README.rst to add explanations on converters/recording + * Merge branch 'sa/info' into 'master' + Sa/info + * Make the info publisher set the robot_description + * Reset the list of publishers when resetting sonar publisher node + * Useless calls + * Normalize log publisher init + * Merge branch 'sa/recorder_cleanup' into 'master' + Sa/recorder cleanup + * Recorder clean up + * Merge branch 'mc/devel' into 'master' + Mc/devel + * Catch error when getting typed data from ALMemory in all converters + * Catch error when getting typed data from ALMemory in Info & MemoryBoolConverter + * Merge branch 'mc/devel' into 'master' + Mc/devel + * hotfix: delete float publisher from CMakeList + * Fix test compilation + * Merge branch 'sa/pub_cleanup' into 'master' + Sa/pub cleanup + I know it is scary, but this actually reduces the code a lot and it still works. + * Remane BasePublisher in BasicPublisher + * Big cleanup of publishers (next) + * Big cleanup of publishers + * Merge branch 'mc/devel' into 'master' + Mc/devel + * hotfix: use toolchain custom ros msgs include + * Fix CMakeList.txt + * Remove include files (integrated in the toolchain) + * Info conv/pub/rec + * Merge branch 'sa/diagnostics_recorder' into 'master' + Sa/diagnostics recorder + * Add diagnostics recorder + * Merge branch 'sa/diagnostics_converter_and_fix' into 'master' + Sa/diagnostics converter and fix + * Remove useless include + * Remove useless call to reset + * Add diagnostics converter/publisher + * Fix naming error + * remove alvalue dependencies + still exist in camera + * Merge branch 'sa/include' into 'master' + Sa/include + Remove useless includes, reorganize them all + * Remove useless include in main src, move the others to minimize their scope + * Remove useless include in converter, move the others to minimize their scope + * Remove useless include in tool, move the others to minimize their scope + * Remove useless include in publisher, move the others to minimize their scope + * Remove useless include in recorder, move the others to minimize their scope + * Cleaning: remove useless include in subscribers + * Prettify #include in subscribers + * Prettify the #include in recorders + * Prettify the #include in publishers + * Prettify the #include in converters + * Merge branch 'sa/setMasterUri' into 'master' + Sa/set master uri + * Move getRobotDescription into tools/ + * Set /robot_description when setting Master URI + * Make JS Converter non-dependent from the Node handle + * Reset tf broadcaster when JS publisher is reset + * Only register new converters if required + * Better mutex and proper stop of the ROS loop when changing master URI + * Merge branch 'mc/devel' into 'master' + Mc/devel + * Update README.rst for function 'registerMemoryConverter' changes + * Add bool msg for memory converter + * Add namespace for DataType enum + * Update README.rst to add new API function + * Add templated function to register memory converter + * delete naoqi_bridge messages + * Add function to get data type from memory_key && add frequency argument + * Only publish/record msgs when the memory data is valid + * Use specific stamped msg for memory converters + * Return max() when there is no data in ALMemory + * Add new API function 'registerMemoryConverter' + * add test for register memory key converter + * add enum for memory data type + * add converters for int/float/string memory key + * Merge branch 'sa/conv_pub_rec_sub_factorize' into 'master' + Factorization of conv/pub/rec/sub init + Put everything that is required to properly initialize sub/pub/rec/conv elements in the corresponding register function + * Remove useless init function + * Move call to sub.reset + * Factorize registration code + * Factorize recorder reset + * Factorize publisher reset + * Remove new memory converters initialization (useless now) + * Factorize conv.reset() in registerConverter() + * Init the converters as soon as they are registered + * Merge branch 'mc/recorder' into 'master' + Mc/recorder + * hotfix: check first list of topics to open a bag only if at least one topic is available + * Merge branch 'devel' into 'master' + Devel + * Merge branch 'documentation' into 'devel' + Documentation + * Update README + * Merge branch 'sa/hotfix' into 'master' + Sa/hotfix + * Change module name in Documentation + * Rename alros_bin to alrosbridge_bin in run.sh + * Add API description in README + * Merge branch 'devel' + Conflicts: + include/alrosbridge/alrosbridge.hpp + manifest.xml + src/alrosbridge.cpp + * rename alsrosconverter to alrosbridge + * Merge branch 'sa/mem_list_improvement' into 'devel' + Sa/mem list improvement + * Accept bool ALValue (convert them in Int) + * Merge branch 'mc/recorder' into 'devel' + Mc/recorder + * Rename API function to be consistant + * Merge branch 'mc/recorder' into 'devel' + Mc/recorder + * Rename API function 'startRecordTopics' to 'startRecordConverters' + Conflicts: + src/alrosbridge.cpp + * Merge branch 'sa/mem_list_doc' into 'devel' + Sa/mem list doc + * Add doc in README about mem key list publication + * hotfix :-) + * Merge branch 'sa/list_of_mem_keys' into 'devel' + Sa/list of mem keys + * Parse the JSON file containing the mem key list and give it to the converter + * Safely return from addMemoryConverters if node handle is not initialized + * Add a recorder for the list of memory keys + * Publish the memory list + * Instanciate a memory list converter (file parsing mocked up) + * Fix reset message at each cycle + * Fix string in message creation in converter + * Add memory list publisher + * Memory list converter + * Add new naoqi messages to manage memory values list + * Add new API method addMemoryConverters (does not do anything for now) + * Re-establish the truth + * Avoid warning message from qimessaging spam + * Merge branch 'mc/devel' into 'devel' + Mc/devel + * Recorder: rename topics in ROSbag as publishers rostopic + * Merge branch 'mc/devel' into 'devel' + Mc/devel + * Recorder: add sonar and laser + * Update package version + * Merge branch 'sa/new_concept' into 'devel' + Sa/new concept + * Merge branch 'sa/concept_test' into 'devel' + Testing the change of concept + * Change concept to store shared_ptr instead of objects themselves + * Change converters constructors to allow construction through make_shared + * Test new concept style + * merge commit + * rviz config with laser and sonar + * hotfix: no callall for empty action vector + * sonar support + * Merge branch 'mc/devel' into 'devel' + Mc/devel + * remove unused functions from converter concept + * Recorder: use colors defined in tools + * Recorder: add coloured logs for recording functions + * Recorder: implement startRecordtopics API function + * Merge branch 'mc/devel' into 'devel' + Mc/devel + * Return a string in stopRecord function + * hotfix: hidden improvement + * Change converter's name + * Add 2 getters for converter's name and subscribed publisher's name + * Merge branch 'sa/devel' into 'devel' + Sa/devel + Small fixes + * No laser for Nao + * Fix spelling mistake + * Remove old calls to publishers replaced by converters + * Merge branch 'sa/devel' into 'devel' + IMU recorder + * Merge branch 'hotfix' into 'devel' + Hotfix + * hotfix: check current path to add it to the bag name + * Remove useless inclusion (already included in another header) + * Add Imu recorder to the bridge + * IMU recorder + * Remove useless ";" + * Merge branch 'mc/devel' into 'devel' + Mc/devel + * Proper way to get relative share folder path && always reload description from file + * bugfix: initialize tf_buffer before converter + * odometry + * Merge branch 'bug26/bagpath' into 'devel' + Bug26/bagpath + * Fix #26 : Use an absolute path to store the bag + * Merge branch 'sa/devel' into 'devel' + Fix #25 + * Fix #25 : log spam due to implicit conversion from ALValue to float vector + * Merge branch 'sa/dev' into 'devel' + Sa/dev + * Add IMU_base for Pepper + * Rename IMU in IMU_torso + * Do not start depth camera if using a Nao + * Converter and publisher for IMU + * Merge branch 'mc/devel' into 'devel' + Mc/devel + * Delete spamming logs + * Merge branch 'mc/devel' into 'devel' + Mc/devel + * hotfix: install share folder for runtime loading + * hotfix: Check if sleep time is positive + initially the pubs are not scheduled in the future + so the time to sleep can be negative, which resolves in infinity + Conflicts: + src/alrosbridge.cpp + * recorder: first check if rosbag is open before writing + * hotfix: install share folder for runtime loading + * hotfix: Check if sleep time is positive + initially the pubs are not scheduled in the future + so the time to sleep can be negative, which resolves in infinity + * Update README.rst + * Merge branch 'sa/dev' into 'devel' + Sa/dev + Some small fixes + * Merge branch 'master' into 'master' + Master + * rename 'start/stop' into 'startPublishing/stopPublishing' + * Update README.rst + * Update README.rst to have it without building it + * Factorize isSubscribed function + Conflicts: + src/publishers/info.hpp + src/publishers/laser.hpp + src/publishers/publisher_base.hpp + * Avoid useless copy + * Remove useless ; + * Package project into an app c++ + * correct camera info frames and publisher + * first version of record and publish via callback + * sonar converter + * laser converter + * Merge branch 'mc/devel' into 'devel' + Mc/devel + * recorder: bugfix #24 recorder base class does not implement all functions + * Package project into an app c++ + * Merge branch 'mc/devel' into 'devel' + Mc/devel + * recorder: add tests for new recorder's API + * recorder: implement data recording in main class + Conflicts: + src/alrosbridge.cpp + * recorder: add methods in 'converter' to know if recording is enabling for a converter instance + * recorder: add concrete recorder instances for each converters + * recorder: add a recorder concept class to instanciate concrete recorders + * Merge branch 'devel' of gitlab.aldebaran.lan:kknese/alrosconverter into mc/devel + Conflicts: + CMakeLists.txt + include/alrosbridge/alrosbridge.hpp + src/alrosbridge.cpp + src/publishers/joint_state.cpp + src/publishers/joint_state.hpp + test/recorder_test.cpp + * camera and joint states + * camera converter callback + * camera converter callback + * test converters + * refactoring cleanup + * recorder namespace + * recorder: add a new instanciation of 'write' method for vector messages + * recorder: clean test recording in alrosbridge.cpp + * Revert "Recorder: clean recorder files from master branch" + This reverts commit 00f2d313b96308f2256dc001af9766d3f417578d. + Conflicts: + include/alrosbridge/alrosbridge.hpp + * Revert "Recorder: remove unuseful dependency" + This reverts commit 4f0e7e677ca241c0d45aa053b4fe3e6cb150c0d2. + * Stop publishing thread before removing the publishers and subscribers + Conflicts: + src/alrosbridge.cpp + * Register callback on qi::application::atStop to handle variable's destruction before run() returns + * demo config + * Merge branch 'master' into 'master' + Master + * Stop publishing thread before removing the publishers and subscribers + * Register callback on qi::application::atStop to handle variable's destruction before run() returns + * camera converter + * initial refactoring, moving files, changing baseclass + * get moveto to be asynchronous + * replace tf listeners by a shared tf buffer + * Merge branch 'master' into 'master' + Master + * Recorder: remove unuseful dependency + * Recorder: clean recorder files from master branch + * Recorder: Add public method to record by topics + * Recorder: Renaming in recorder & test recording by topics + * get moveto to be asynchronous + * replace tf listeners by a shared tf buffer + * rm consolebridge dependency + * rm consolebridge dependency + * Merge branch 'sambrose/master' into 'master' + Sambrose/master + Some small fixes to avoid segfault or nasty stuff when leaving the program. + * Avoid segfault if setting the master URI, but no task is scheduled + * Do not use unlock, scope the mutex + * Avoid segfault when quiting without having set a Master URI + * add refactoring test + * first test for callback refactor + * Merge branch 'master' into 'master' + Master + * Recorder: Add time to bag name + * Recorder: Add a basic test for recorder class + * Recorder: First draft of a ROSbag recorder API + * use latest urdf file + * cleaner NAO - Pepper separation in Publisher registration + * remove useless checks as we can now support proper latching + * properly schedule publishers in case of ROS_MASTER_URI reset. + * add boost callback test + * basefootprint publisher for nao + add nao_joint_states.cpp + * fix time stamp + * add pepper rviz config file + * exclude odometry from joint_state_publisher + * Merge branch 'sambrose/master' into 'master' + Automatically deploy ros from toolchain + Hey ! + This is a very small MR to: + 1) Test the MR behavior when using branches on the same project + 2) To share my great progress: allow the ros toolchain to be deployed to the robot just by adding a word :D + Hope you will like it ^^ + * Add ros dependency to qiproject + This will automatically deploy ros package on the robot when using + qibuild deploy + * Merge branch 'master' into 'master' + Master + Fix issue #11 + - Correct frame transform in moveto + - Add correct yaw orientation to moveto command + * Correct tf2 time lookup in moveto && Add orientation to moveto command + * add NAO rviz config file + * bugfix: publish correct depth_camera encoding + * reduce default CPU usage by not using a tf2 listener if no subscriber + * Do not advertise compressed depth topics for non depth images + This fixes #3 + * remove verbosity in laser + * check against AL::kDepthCamera instead of 2 + * use camera with correct frequency + removes hardcoded 20 + * bugfix: correct parent path + * Merge branch 'master' of gitlab.aldebaran.lan:kknese/alrosconverter + * load urdf from file if no rosparam + * start depth camera only on pepper + * Merge branch 'update_doc' into 'master' + Update doc + * Moving section compiling into Getting started. + It is easier to read the documentation this way: In getting start it's + straightforward no need to go to end of page to understand how to install the + ros bridge. + * fix correct robot id + * fix runtime problem + * update the todos + * switch to tf2 + * first import of the current naoqi msgs + * add a basic way of importing messages and having them be part of our headers + * update README + * clean msg folder + * update doc for Android and misc clean-ups + * add a method to set the netowork interface too + * add proper timestamps for the images / camera info + * Revert "remove a memory copy for images" + This reverts commit 72b02187b48bafcfdee7eaa889d0b185bec57793. + * Merge branch 'master' of gitlab.aldebaran.lan:kknese/alrosconverter + Conflicts: + CMakeLists.txt + src/alrosbridge.cpp + * 2d nav goal (rviz) moveto support + * better handling of potential log explosion + * add a log bridge + * fix abusive rate for info + * Merge branch 'master' of gitlab.aldebaran.lan:kknese/alrosconverter + Conflicts: + CMakeLists.txt + * support for teleop subscriber + * quickfix: return correct robot string + * add the first draft of an info module + * fix compilation + * Merge branch 'master' of gitlab.aldebaran.lan:kknese/alrosconverter + * quickfix: return correct robot name + * quickfix: remove whitespaces in string compare + * fix crashes when resetting the master URI + * properly call the subscribe/unsusbcribe methods for sonar + * increase laser frequency to 10hz + * limit laser range to 1.5 to eliminate noise + * correct odometry frame + * motion twist subscriber + * fix camera frames so that they are the optical frame + * use a proper raw topic + * only publish lasers when on Pepper + * add a sonar publisher + * add a way to know the ID of the robot and unify publisher constructors + * add a bit more specs + * clean reset logging + * remove a memory copy for images + * disabled verbosity in lasers + * unregister properly from VideoDevice when quitting or resetting + * initial support for laser scan + * Merge branch 'master' of gitlab.aldebaran.lan:kknese/alrosconverter + Conflicts: + src/publishers/camera.cpp + * publish odom frame + * expose name in print statement + * fix overlap of camera_infos + * use proper image_Transport API and show loadable plugins + * fix install of package with latest qibuild + * update docs + * first draft of diagnostics + A proper solution would publish al ldiagnostics at different + rates and use an aggregator as usually done. + We will check with the CPU usage whether this is possible + * Merge branch 'camera_info' + Conflicts: + src/publishers/camera.cpp + src/publishers/camera.hpp + * Merge branch 'master' of gitlab.aldebaran.lan:kknese/alrosconverter + * minimize the memory copies for the image + * Merge branch 'master' of gitlab.aldebaran.lan:kknese/alrosconverter + Conflicts: + include/alrosbridge/alrosbridge.hpp + src/alrosbridge.cpp + * implement depth image with camera info + * quickfix: resolve segfault in schedule publisher + hint: prevent a re-alloc of memory in all_publisher variable since this leads to invalid pointer + * const pointer implementation + * fix a crash with undefined pointer + * use the create_module macro as it should be + * update docs + * Merge branch 'master' of gitlab.aldebaran.lan:kknese/alrosconverter + Conflicts: + include/alrosbridge/alrosbridge.hpp + include/alrosbridge/publisher/publisher.hpp + * add license and public interface doc + * add license and public interface doc + * rename project name to alrosbridge + * rename external service entry point + * remove legacy code + * quickfix: change CMake for filechange + * enable all default publisher + * renamend autoload entry point + * remove constructor with nodehandle parameter + * expose public interface headers in include folder + * Merge branch 'master' of gitlab.aldebaran.lan:kknese/alrosconverter + * small cleanups + * Merge branch 'master' of gitlab.aldebaran.lan:kknese/alrosconverter + * Merge branch 'master' into 'master' + clean base classes + This will be useful for diagnostics too: I don't want to implement yet another base class there. + * cleanup: remove unused interface + * clean base classes + * quick fix: enable publishing in alrosbridge + * Merge branch 'master' into 'master' + allow for different publisher frequencies + * allow for different publisher frequencies + * Merge branch 'camera_publisher' + * remove constructor with nodehandle + no reset by initialization + * bugfix: single reset/init point + * remove verbosity in publishing + * added a bgr8 front camera publisher + * add precisions about topics + * update doc + * update documentation + * Merge branch 'master' of gitlab.aldebaran.lan:kknese/alrosconverter + * update README + * trigger ros-init without siginthandler + * add basic doc + * basic naoqi2 module with start/stop publising + has a minor bug of destroying the module + * main.cpp for external binary execution + * exclude naoqi autoload registration + * implement operator==() + * introduce crtp + * send dynamic float array for benchmark + * updated readme + * Merge branch 'master' of gitlab.aldebaran.lan:kknese/alrosconverter + * add robot state publisher in code + * publishing joint states in global namespace + * add test_primitives + * add naoqi agnostic ros code for benchmarking + * add another TODO + * update README + * Merge branch 'master' of gitlab.aldebaran.lan:kknese/alrosconverter + * code cleanup + * exclude static ros function in ros_env.hpp + * added joint_state_publisher + * increase publish rate to 15 + * use linux64 toolchain pkg for local compile + * add a README file + * basic bridge example for int and strings + * basic publisher example (string, int) + * support for multiple publishers + * base structure of bridge concept + * adding simple publisher + * initial commit + * Contributors: Guillaume JACOB, Karsten KNESE, Karsten Knese, Laurent GEORGE, Marine CHAMOUX, Surya AMBROSE, Surya Ambrose, Vincent Rabaud, sambrose, zygopter + + -- Victor Paléologue Sun, 17 May 2015 12:08:00 -0000 + + diff --git a/debian/changelog.em b/debian/changelog.em deleted file mode 100644 index 3585909..0000000 --- a/debian/changelog.em +++ /dev/null @@ -1,7 +0,0 @@ -@[for change_version, change_date, changelog, main_name, main_email in changelogs]@(Package) (@(change_version)@(DebianInc)@(Distribution)) @(Distribution); urgency=high - -@(changelog) - - -- @(main_name) <@(main_email)> @(change_date) - -@[end for] diff --git a/debian/compat b/debian/compat new file mode 100644 index 0000000..ec63514 --- /dev/null +++ b/debian/compat @@ -0,0 +1 @@ +9 diff --git a/debian/compat.em b/debian/compat.em deleted file mode 100644 index 7a87216..0000000 --- a/debian/compat.em +++ /dev/null @@ -1 +0,0 @@ -@(debhelper_version) diff --git a/debian/control b/debian/control new file mode 100644 index 0000000..84699a4 --- /dev/null +++ b/debian/control @@ -0,0 +1,14 @@ +Source: ros-humble-naoqi-driver +Section: misc +Priority: optional +Maintainer: Victor Paléologue +Build-Depends: debhelper (>= 9.0.0), libboost-all-dev, ros-humble-action-msgs, ros-humble-ament-cmake, ros-humble-ament-lint-auto , ros-humble-ament-lint-common , ros-humble-cv-bridge, ros-humble-diagnostic-msgs, ros-humble-diagnostic-updater, ros-humble-geometry-msgs, ros-humble-image-transport, ros-humble-kdl-parser, ros-humble-naoqi-bridge-msgs (>= 2.0.0), ros-humble-naoqi-libqi, ros-humble-naoqi-libqicore, ros-humble-rclcpp, ros-humble-rclcpp-action, ros-humble-robot-state-publisher, ros-humble-rosidl-default-generators, ros-humble-sensor-msgs, ros-humble-tf2-geometry-msgs, ros-humble-tf2-msgs, ros-humble-tf2-ros, ros-humble-ros-workspace, ros-humble-rosidl-typesupport-fastrtps-c, ros-humble-rosidl-typesupport-fastrtps-cpp +Homepage: +Standards-Version: 3.9.2 + +Package: ros-humble-naoqi-driver +Architecture: any +Depends: ${shlibs:Depends}, ${misc:Depends}, libboost-all-dev, ros-humble-action-msgs, ros-humble-cv-bridge, ros-humble-image-transport, ros-humble-kdl-parser, ros-humble-naoqi-bridge-msgs (>= 2.0.0), ros-humble-naoqi-libqi, ros-humble-naoqi-libqicore, ros-humble-rclcpp, ros-humble-rclcpp-action, ros-humble-robot-state-publisher, ros-humble-tf2-ros, ros-humble-ros-workspace +Conflicts: ros-humble-nao-driver, ros-humble-naoqi-rosbridge +Description: Driver module between Aldebaran's NAOqiOS and ROS2. + It publishes all sensor and actuator data as well as basic diagnostic for battery, temperature. It subscribes also to RVIZ simple goal and cmd_vel for teleop. diff --git a/debian/control.em b/debian/control.em deleted file mode 100644 index 6d7b65c..0000000 --- a/debian/control.em +++ /dev/null @@ -1,14 +0,0 @@ -Source: @(Package) -Section: misc -Priority: optional -Maintainer: @(Maintainer) -Build-Depends: debhelper (>= @(debhelper_version).0.0), @(', '.join(BuildDepends)) -Homepage: @(Homepage) -Standards-Version: 3.9.2 - -Package: @(Package) -Architecture: any -Depends: ${shlibs:Depends}, ${misc:Depends}, @(', '.join(Depends)) -@[if Conflicts]Conflicts: @(', '.join(Conflicts))@\n@[end if]@ -@[if Replaces]Replaces: @(', '.join(Replaces))@\n@[end if]@ -Description: @(Description) diff --git a/debian/copyright.em b/debian/copyright similarity index 50% rename from debian/copyright.em rename to debian/copyright index bc82fd5..6cd10c2 100644 --- a/debian/copyright.em +++ b/debian/copyright @@ -1,11 +1,7 @@ Format: Bloom subset of https://www.debian.org/doc/packaging-manuals/copyright-format/1.0/ -Upstream-Name: @(Name) -@[if BugTracker]Upstream-Contact: @(BugTracker)@\n@[end if]@ -@[if Source]Source: @(Source)@\n@[end if]@ -@[for License, Text in Licenses]@ +Upstream-Name: naoqi_driver Files: See file headers in repository for details Copyright: See package copyright in source code for details -License: @(License) - @(Text) -@[end for]@ +License: BSD + See repository for full license text diff --git a/debian/gbp.conf b/debian/gbp.conf new file mode 100644 index 0000000..3283f6f --- /dev/null +++ b/debian/gbp.conf @@ -0,0 +1,3 @@ +[git-buildpackage] +upstream-tag=release/humble/naoqi_driver/2.1.1-1 +upstream-tree=tag diff --git a/debian/gbp.conf.em b/debian/gbp.conf.em deleted file mode 100644 index ad24a16..0000000 --- a/debian/gbp.conf.em +++ /dev/null @@ -1,3 +0,0 @@ -[git-buildpackage] -upstream-tag=@(release_tag) -upstream-tree=tag diff --git a/debian/rules.em b/debian/rules similarity index 72% rename from debian/rules.em rename to debian/rules index 2ab7b14..2266737 100755 --- a/debian/rules.em +++ b/debian/rules @@ -13,7 +13,7 @@ export DH_VERBOSE=1 # https://code.ros.org/trac/ros/ticket/2977 # https://code.ros.org/trac/ros/ticket/3842 export LDFLAGS= -export PKG_CONFIG_PATH=@(InstallationPrefix)/lib/pkgconfig +export PKG_CONFIG_PATH=/opt/ros/humble/lib/pkgconfig # Explicitly enable -DNDEBUG, see: # https://github.com/ros-infrastructure/bloom/issues/327 export DEB_CXXFLAGS_MAINT_APPEND=-DNDEBUG @@ -24,24 +24,24 @@ endif DEB_HOST_GNU_TYPE ?= $(shell dpkg-architecture -qDEB_HOST_GNU_TYPE) %: - dh $@@ -v --buildsystem=cmake --builddirectory=.obj-$(DEB_HOST_GNU_TYPE) + dh $@ -v --buildsystem=cmake --builddirectory=.obj-$(DEB_HOST_GNU_TYPE) override_dh_auto_configure: # In case we're installing to a non-standard location, look for a setup.sh # in the install tree and source it. It will set things like # CMAKE_PREFIX_PATH, PKG_CONFIG_PATH, and PYTHONPATH. - if [ -f "@(InstallationPrefix)/setup.sh" ]; then . "@(InstallationPrefix)/setup.sh"; fi && \ + if [ -f "/opt/ros/humble/setup.sh" ]; then . "/opt/ros/humble/setup.sh"; fi && \ dh_auto_configure -- \ - -DCMAKE_INSTALL_PREFIX="@(InstallationPrefix)" \ - -DAMENT_PREFIX_PATH="@(InstallationPrefix)" \ - -DCMAKE_PREFIX_PATH="@(InstallationPrefix)" \ + -DCMAKE_INSTALL_PREFIX="/opt/ros/humble" \ + -DAMENT_PREFIX_PATH="/opt/ros/humble" \ + -DCMAKE_PREFIX_PATH="/opt/ros/humble" \ $(BUILD_TESTING_ARG) override_dh_auto_build: # In case we're installing to a non-standard location, look for a setup.sh # in the install tree and source it. It will set things like # CMAKE_PREFIX_PATH, PKG_CONFIG_PATH, and PYTHONPATH. - if [ -f "@(InstallationPrefix)/setup.sh" ]; then . "@(InstallationPrefix)/setup.sh"; fi && \ + if [ -f "/opt/ros/humble/setup.sh" ]; then . "/opt/ros/humble/setup.sh"; fi && \ dh_auto_build override_dh_auto_test: @@ -49,19 +49,19 @@ override_dh_auto_test: # in the install tree and source it. It will set things like # CMAKE_PREFIX_PATH, PKG_CONFIG_PATH, and PYTHONPATH. echo -- Running tests. Even if one of them fails the build is not canceled. - if [ -f "@(InstallationPrefix)/setup.sh" ]; then . "@(InstallationPrefix)/setup.sh"; fi && \ + if [ -f "/opt/ros/humble/setup.sh" ]; then . "/opt/ros/humble/setup.sh"; fi && \ dh_auto_test || true override_dh_shlibdeps: # In case we're installing to a non-standard location, look for a setup.sh # in the install tree and source it. It will set things like # CMAKE_PREFIX_PATH, PKG_CONFIG_PATH, and PYTHONPATH. - if [ -f "@(InstallationPrefix)/setup.sh" ]; then . "@(InstallationPrefix)/setup.sh"; fi && \ - dh_shlibdeps -l$(CURDIR)/debian/@(Package)/@(InstallationPrefix)/lib/ + if [ -f "/opt/ros/humble/setup.sh" ]; then . "/opt/ros/humble/setup.sh"; fi && \ + dh_shlibdeps -l$(CURDIR)/debian/ros-humble-naoqi-driver//opt/ros/humble/lib/ override_dh_auto_install: # In case we're installing to a non-standard location, look for a setup.sh # in the install tree and source it. It will set things like # CMAKE_PREFIX_PATH, PKG_CONFIG_PATH, and PYTHONPATH. - if [ -f "@(InstallationPrefix)/setup.sh" ]; then . "@(InstallationPrefix)/setup.sh"; fi && \ + if [ -f "/opt/ros/humble/setup.sh" ]; then . "/opt/ros/humble/setup.sh"; fi && \ dh_auto_install diff --git a/debian/source/format b/debian/source/format new file mode 100644 index 0000000..163aaf8 --- /dev/null +++ b/debian/source/format @@ -0,0 +1 @@ +3.0 (quilt) diff --git a/debian/source/format.em b/debian/source/format.em deleted file mode 100644 index 9666bf4..0000000 --- a/debian/source/format.em +++ /dev/null @@ -1 +0,0 @@ -3.0 (@(format)) diff --git a/debian/source/options.em b/debian/source/options similarity index 81% rename from debian/source/options.em rename to debian/source/options index 8c4c78b..8bc9182 100644 --- a/debian/source/options.em +++ b/debian/source/options @@ -1,6 +1,5 @@ -@[if format and format == 'quilt']@ # Automatically add upstream changes to the quilt overlay. # http://manpages.ubuntu.com/manpages/trusty/man1/dpkg-source.1.html # This supports reusing the orig.tar.gz for debian increments. auto-commit -@[end if] +