Compare commits

...

3 Commits

Author SHA1 Message Date
a60a1784f7 Path fixes etc 2024-09-19 11:09:24 -03:00
78271404fb Multi stage build 2024-09-19 10:44:55 -03:00
84b80637bc Tutorial for cpp 2024-09-19 10:37:09 -03:00
7 changed files with 119 additions and 18 deletions

View File

@ -11,7 +11,7 @@ PACKAGE_DESCRIPTION:
multiline: true
MAINTAINER_NAME: No Reply
MAINTAINER_EMAIL: "{{MAINTAINER_NAME|slugify}}@spirirobotics.com"
MAINTAINER_EMAIL: "{{MAINTAINER_NAME|lower|replace(' ', '.')}}@spirirobotics.com"
LICENSE: BSD
#We use a custom launch script to ensure that rosrun logs to console and have it not accidently launch the master node itself, which can be hard to diagnose
LANGUAGES:
@ -22,12 +22,9 @@ LANGUAGES:
- Python
- CPP
RUN_COMMAND: rosrun {{PACKAGE_NAME}} {{"main.py" if 'Python' in LANGUAGES elif "CPP" in LANGAUGES "main"}}
RUN_COMMAND: rosrun {{ PACKAGE_NAME }} {{ "main.py" if 'Python' in LANGUAGES else "main" if "CPP" in LANGUAGES else "yourcommandGoes here" }}
HEALTHCHECK:
defualt: --start-period=60s --start-interval=1s CMD /ros_entrypoint.sh rostopic list
type: str
help: |
This health check command should return 0 when your service is running properly.
The default healthcheck just checks to see if we can reach the ROS master.
Providing a good health check is left as an excersize to the reader.
help: It's important to have a good health check. This health check just sees if we can talk to the ROS master

View File

@ -192,7 +192,14 @@ include_directories(
# DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}
# )
{% if "CPP" in LANGUAGES %}
## Declare a C++ executable
add_executable(main src/main.cpp)
target_link_libraries(main ${catkin_LIBRARIES})
{% endif %}
{%if "Python" in LANGUAGES%}
#Include a python command
catkin_install_python(PROGRAMS scripts/main.py
DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION}
)

View File

@ -1,5 +1,6 @@
# Stage 1: Build Stage
FROM git.spirirobotics.com/spiri/services-ros1-core:main AS builder
FROM git.spirirobotics.com/spiri/services-ros1-core:main AS devenv
#We need to make sure to source the ROS environment in our dockerfile
SHELL ["/bin/bash", "-c"]
@ -10,19 +11,29 @@ RUN apt-get install --yes python3-rosdep python3-rosinstall python3-rosinstall-g
WORKDIR /root/catkin_ws/src
COPY ./ .
WORKDIR /root/catkin_ws
RUN /bin/bash -c "source /opt/ros/noetic/setup.bash && rosdep init"
RUN /bin/bash -c "source /opt/ros/noetic/setup.bash && rosdep update"
RUN /bin/bash -c "source /opt/ros/noetic/setup.bash && rosdep install --from-paths src -y"
RUN /bin/bash -c "source /opt/ros/noetic/setup.bash && catkin_make"
RUN /bin/bash -c "source /opt/ros/noetic/setup.bash && catkin_make install"
WORKDIR /root/catkin_ws
COPY ./ {{PACKAGE_NAME}}
RUN apt-get clean
HEALTHCHECK {{HEALTHCHECK}}
# Command to run your application
CMD {{RUN_COMMAND}} --wait --screen
WORKDIR /root/catkin_ws
RUN /bin/bash -c "source /opt/ros/noetic/setup.bash && rosdep init"
RUN /bin/bash -c "source /opt/ros/noetic/setup.bash && rosdep update"
RUN /bin/bash -c "source /opt/ros/noetic/setup.bash && rosdep install --from-paths src -y"
RUN echo "source /opt/ros/noetic/setup.bash" >> ~/.bashrc
RUN echo "source /root/catkin_ws/devel/setup.bash" >> ~/.bashrc
FROM devenv AS build
RUN /bin/bash -c "source /opt/ros/noetic/setup.bash && catkin_make"
RUN /bin/bash -c "source /opt/ros/noetic/setup.bash && catkin_make install"
WORKDIR /root/catkin_ws

View File

@ -4,10 +4,11 @@ services:
build:
context: .
dockerfile: Dockerfile
target: devenv
environment:
- "ROS_MASTER_URI=http://ros-master:11311"
volumes:
- ./:/root/catkin_ws/src/myproject
- ./:/root/catkin_ws/src/{{PROJECT_NAME}}
command: bash -c "tail -f /dev/null"
networks:
- sdk

View File

@ -0,0 +1,85 @@
#include "ros/ros.h"
#include "std_msgs/String.h"
#include <sstream>
/**
* This tutorial demonstrates simple sending of messages over the ROS system.
*/
int main(int argc, char **argv)
{
/**
* The ros::init() function needs to see argc and argv so that it can perform
* any ROS arguments and name remapping that were provided at the command line.
* For programmatic remappings you can use a different version of init() which takes
* remappings directly, but for most command-line programs, passing argc and argv is
* the easiest way to do it. The third argument to init() is the name of the node.
*
* You must call one of the versions of ros::init() before using any other
* part of the ROS system.
*/
ros::init(argc, argv, "talker");
/**
* NodeHandle is the main access point to communications with the ROS system.
* The first NodeHandle constructed will fully initialize this node, and the last
* NodeHandle destructed will close down the node.
*/
ros::NodeHandle n;
/**
* The advertise() function is how you tell ROS that you want to
* publish on a given topic name. This invokes a call to the ROS
* master node, which keeps a registry of who is publishing and who
* is subscribing. After this advertise() call is made, the master
* node will notify anyone who is trying to subscribe to this topic name,
* and they will in turn negotiate a peer-to-peer connection with this
* node. advertise() returns a Publisher object which allows you to
* publish messages on that topic through a call to publish(). Once
* all copies of the returned Publisher object are destroyed, the topic
* will be automatically unadvertised.
*
* The second parameter to advertise() is the size of the message queue
* used for publishing messages. If messages are published more quickly
* than we can send them, the number here specifies how many messages to
* buffer up before throwing some away.
*/
ros::Publisher chatter_pub = n.advertise<std_msgs::String>("chatter", 1000);
ros::Rate loop_rate(10);
/**
* A count of how many messages we have sent. This is used to create
* a unique string for each message.
*/
int count = 0;
while (ros::ok())
{
/**
* This is a message object. You stuff it with data, and then publish it.
*/
std_msgs::String msg;
std::stringstream ss;
ss << "hello world " << count;
msg.data = ss.str();
ROS_INFO("%s", msg.data.c_str());
/**
* The publish() function is how you send messages. The parameter
* is the message object. The type of this object must agree with the type
* given as a template parameter to the advertise<>() call, as was done
* in the constructor above.
*/
chatter_pub.publish(msg);
ros::spinOnce();
loop_rate.sleep();
++count;
}
return 0;
}