Showing posts with label gazebo. Show all posts
Showing posts with label gazebo. Show all posts

Wednesday, November 21, 2018

Start Gazebo and PX4 SITL separately

  • Terminal 1
make posix_sitl_default gazebo no_sim=1

  • Terminal 2
# PX4 gazebo plugins export GAZEBO_PLUGIN_PATH=${GAZEBO_PLUGIN_PATH}:/home/user/px4/Firmware/build/posix_sitl_default/build_gazebo export GAZEBO_MODEL_PATH=${GAZEBO_MODEL_PATH}:/home/user/px4/Firmware/Tools/sitl_gazebo/models # add iris model into warehouse world #run gazebo --verbose /home/user/px4/Firmware/Tools/sitl_gazebo/worlds/warehouse.world

Add iris into warehouse.world

<?xml version="1.0" ?> <sdf version="1.5"> <world name="default"> <!-- A global light source --> <include> <uri>model://sun</uri> </include> <!-- A ground plane --> <include> <uri>model://ground_plane</uri> </include> <include> <uri>model://asphalt_plane</uri> </include> <!--add iris model for example --> <include> <uri>model://iris</uri> <pose>1.01 0.98 0.83 0 0 1.14</pose> </include>

Note

Try to add model with gz command, the model add into the world model list but not visible

gz model --spawn-file=iris.sdf --model-name=iaaa -p 1.01 0.98 0.83 0 0 1.14

Sunday, November 18, 2018

Gazebo ImageStamped message to OpenCV

Convert Gazebo camera ImageStamped message to OpenCV Mat

Client code subscribe to gazebo image topic message type ImageStamped and view the image as opencv mat

  • Terminal 1 (run gazebo)
make posix_sitl_default gazebo_typhoon_h480
  • Termianl 2 (view topics and topic message)
gz topic -l # /gazebo/default/typhoon_h480/camera/link/irlock /gazebo/default/typhoon_h480/cgo3_camera_link/camera/cmd /gazebo/default/typhoon_h480/cgo3_camera_link/camera/image /gazebo/default/typhoon_h480/cgo3_camera_link/camera_imu/imu /gazebo/default/typhoon_h480/cgo3_camera_link/wrench /gazebo/default/typhoon_h480/cgo3_horizontal_arm_link/wr # gz topic -i /gazebo/default/typhoon_h480/cgo3_camera_link/camera/image Type: gazebo.msgs.ImageStamped
  • Terminal 2 (run the app)
cd build cmake .. make ../bin/viewer

  • callback function
void cb(ConstImageStampedPtr &msg) { int width; int height; char *data; width = (int) msg->image().width(); height = (int) msg->image().height(); //+1 for null terminate data = new char[msg->image().data().length() + 1]; memcpy(data, msg->image().data().c_str(), msg->image().data().length()); //gazebo output rgb data //PixelFormat.R8G8B8 cv::Mat image(height, width, CV_8UC3, data); cv::imshow("camera", image); cv::waitKey(1); delete data; // DO NOT FORGET TO DELETE THIS, // ELSE GAZEBO WILL TAKE ALL YOUR MEMORY }
cmake_minimum_required(VERSION 2.8) project(gz_viewer) set(CMAKE_CXX_STANDARD 11) set(EXECUTABLE_OUTPUT_PATH ${CMAKE_SOURCE_DIR}/bin) find_package(gazebo REQUIRED) include_directories(${GAZEBO_INCLUDE_DIRS}) link_directories(${GAZEBO_LIBRARY_DIRS}) list(APPEND CMAKE_CXX_FLAGS "${GAZEBO_CXX_FLAGS}") find_package( OpenCV REQUIRED ) add_executable(viewer viewer.cpp) target_link_libraries(viewer ${OpenCV_LIBS} ${GAZEBO_LIBRARIES} pthread)

Reference

Friday, November 9, 2018

Gazebo topic subscribe

Gazebo communicates on TCP/IP sockets Messages are sent on named channels called topics via publishers. On the other side of a topic are subscribers, which receive callbacks when messages arrive.

gz topic -l list the topic on running system

Subscriber

Demo code subscribe to /gazebo/default/world_stats

  • topic list
gz topic -l .... /gazebo/default/world_control /gazebo/default/world_stats /gazebo/motor_failure_num /gazebo/server/control /gazebo/world/modify
  • topic info
gz topic -i /gazebo/default/world_stats Type: gazebo.msgs.WorldStatistics Publishers: 192.168.2.200:39165 Subscribers:
  • topic message view
# gz topic -e (echo) gz topic -v /gazebo/default/world_stats



Write code

  • Reference

  • My GIT

  • cmake file (not include project name and minimum_required)

find_package(gazebo REQUIRED) include_directories(${GAZEBO_INCLUDE_DIRS}) link_directories(${GAZEBO_LIBRARY_DIRS}) list(APPEND CMAKE_CXX_FLAGS "${GAZEBO_CXX_FLAGS}") add_executable(sub_demo sub_demo.cpp) target_link_libraries(sub_demo ${GAZEBO_LIBRARIES} pthread)
  • sub_demo source
#include <gazebo-7/gazebo/transport/TransportIface.hh> #include <gazebo-7/gazebo/msgs/msgs.hh> #include <gazebo-7/gazebo/gazebo_client.hh> #include <iostream> #include <csignal> const std::string TOPIC = "/gazebo/default/world_stats"; void my_shutdown(int signal){ std::cout<<"shutdown gazebo client" << std::endl; gazebo::client::shutdown(); exit(0); } void cb(ConstWorldStatisticsPtr &_msg){ std::cout << _msg->DebugString() << std::endl; } int main(int argc, char **argv){ signal (SIGINT, my_shutdown); gazebo::client::setup(argc, argv); //create node for communication gazebo::transport::NodePtr node(new gazebo::transport::Node()); node->Init(); //subscribe to topic gazebo::transport::SubscriberPtr sub = node->Subscribe(TOPIC, cb); while(true){ gazebo::common::Time::MSleep(100); } return 0; }

Friday, October 12, 2018

ROS Follow the line

Gazebo image topics

  • Terminal1 (gazebo turtlebot)
roslaunch turtlebot_gazebo turtlebot_world.launch
  • Terminal2
rostopic list
  • depth camera
  • rgb camera
    • raw: raw image
    • compress: compress image
    • theora: compress video

ROS sent image useing sensor_msgs/Image

Follower node

  • subscribe to /camera/rgb/image_raw topic receive Image msg
#!/usr/bin/env python import rospy from sensor_msgs.msg import Image def image_callback(msg): pass def main(): rospy.init_node("follower") rospy.loginfo("start node") sub = rospy.Subscriber("/camera/rgb/image_raw", Image, image_callback) while not rospy.is_shutdown(): rospy.spin() if __name__ == "__main__": main()
  • Set node permission (chmod +x)
  • Run in separated Terminal
rosrun <package_name> follower.py
  • Check that the node is running
  • Get node info with rosnode info /follower
  • Check message receive interval
rostopic hz /camera/rgb/image_raw subscribed to [/camera/rgb/image_raw] WARNING: may be using simulated time average rate: 30.208 min: 0.010s max: 0.060s std dev: 0.01642s window: 30 average rate: 28.061 min: 0.010s max: 0.060s std dev: 0.01638s window: 56

Setup follow the line

launch file and projects structure

  • launch file
    • worlds
  • gazebo resource
    • materials
├── launch │   └── follow.launch ├── materials │   ├── course.material │   └── course.png ├── models ├── scripts │   └── follower.py ├── src └── worlds └── course.world
<?xml version="1.0"?> <launch> <env name="GAZEBO_RESOURCE_PATH" value="$(find follow_bot)/materials:$(optenv GAZEBO_RESOURCE_PATH)" /> <include file="$(find gazebo_ros)/launch/empty_world.launch"> <arg name="world_name" value="$(find follow_bot)/worlds/course.world"/> </include> <include file="$(find turtlebot_gazebo)/launch/includes/kobuki.launch.xml"> <arg name="base" value="kobuki"/> <arg name="stacks" value="hexagons"/> <arg name="3d_sensor" value="kinect"/> </include> </launch>

Note: launch file set GAZEBO_RESOURCE_PATH environment variable using env tag

View image

#!/usr/bin/env python import rospy from sensor_msgs.msg import Image import cv2 import cv_bridge class Follower(object): def __init__(self): self._bridge = cv_bridge.CvBridge() sub = rospy.Subscriber("/camera/rgb/image_raw", Image, self.image_callback) def image_callback(self, msg): image = self._bridge.imgmsg_to_cv2(msg,desired_encoding='bgr8') cv2.imshow("window", image) cv2.waitKey(3) def on_shutdown(): rospy.loginfo("shutdown") cv2.destroyAllWindows() def main(): rospy.init_node("follower") rospy.loginfo("start node") rospy.on_shutdown(on_shutdown) while not rospy.is_shutdown(): follower = Follower() rospy.spin() if __name__ == "__main__": main()

Note: When we use the cv2.namedWindow Method the Window was freeze check the line solution

Detecting the line

  • Find the yellow line
lower_yellow = numpy.array([ 50, 50, 170]) upper_yellow = numpy.array([255, 255, 190]) mask = cv2.inRange(hsv, lower_yellow, upper_yellow)
  • left: orignal
  • center: mask imaged (binary)
  • right: masked image (extrat only the line from orignal image)

Find line center

  • Mask image and take only relevant part (closer path front to the robot)

  • Find line center with cv2 moments method
  • For debug draw circle on line centroid
M = cv2.moments(mask) if M['m00'] > 0: cx = int(M['m10']/M['m00']) cy = int(M['m01']/M['m00']) cv2.circle(image, (cx, cy), 20, (0,0,255), -1)

- Public `Twist` message , calc z angular value ```python #delta/ error between line center to image center delta = cx - w/2 twist = Twist() twist.linear.x = 0.2 twist.angular.z = -float(delta) / 100 self._cmd_vel_pub.publish(twist)

Final demo

Reference

Sunday, October 7, 2018

Gazebo camera plugin

resource

Plugins can be added to any of the main elements of a URDF - a <robot>, <link>, or <joint> depending on what the scope and purpose of the plugin is. when add <plugin> to urdf we wrap it with <gazebo> element

<gazebo reference="<link_name>"> <plugin name="camera_controller" filename="libgazebo_ros_camera.so"> ... plugin parameters ... </plugin> </gazebo>

Gazebo Camera

<gazebo reference="camera_link"> <sensor type="camera" name="camera"> <update_rate>30.0</update_rate> <camera name="head"> <horizontal_fov>1.3962634</horizontal_fov> <image> <width>800</width> <height>800</height> <format>R8G8B8</format> </image> <clip> <near>0.02</near> <far>300</far> </clip> <noise> <type>gaussian</type> <mean>0.0</mean> <stddev>0.007</stddev> </noise> </camera> <plugin name="camera_controller" filename="libgazebo_ros_camera.so"> <alwaysOn>true</alwaysOn> <updateRate>0.0</updateRate> <cameraName>bot/camera</cameraName> <imageTopicName>image_raw</imageTopicName> <cameraInfoTopicName>camera_info</cameraInfoTopicName> <frameName>camera_link</frameName> <hackBaseline>0.07</hackBaseline> <distortionK1>0.0</distortionK1> <distortionK2>0.0</distortionK2> <distortionK3>0.0</distortionK3> <distortionT1>0.0</distortionT1> <distortionT2>0.0</distortionT2> </plugin> </sensor> </gazebo> </robot>

Name and Topic

<sensor type="camera" name="camera">
  • sensor name must be unique and used by cameraName
<cameraName>bot/camera</cameraName> <imageTopicName>image_raw</imageTopicName> <cameraInfoTopicName>camera_info</cameraInfoTopicName>

rostopic list

rostopic list /bot/camera/camera_info /bot/camera/image_raw /bot/camera/image_raw/compressed /bot/camera/image_raw/compressed/parameter_descriptions /bot/camera/image_raw/compressed/parameter_updates /bot/camera/image_raw/compressedDepth /bot/camera/image_raw/compressedDepth/parameter_descriptions /bot/camera/image_raw/compressedDepth/parameter_updates /bot/camera/image_raw/theora /bot/camera/image_raw/theora/parameter_descriptions /bot/camera/image_raw/theora/parameter_updates /bot/camera/parameter_descriptions /bot/camera/parameter_updates ...

tf

The coordinate frame the image is published under in the tf tree.

<frameName>camera_link</frameName>

Test

  • Terminal 1(launch gazebo)
roslaunch gazebo_ros empty_world.launch
  • Terminal 2(spawn)
#from urdf path rosrun gazebo_ros spawn_model -file camera.urdf -urdf -model bot
  • Terminal 3(rqt)
rqt # Plugins -> Visualization-> image viewer # From combo /bot/camera/image_raw
  • From gazebo add model in the front of camera

  • Check view in rqt

Full urdf code

<?xml version="1.0"?> <robot name="bot"> <!-- Camera --> <link name="camera_link"> <collision> <origin xyz="0 0 0" rpy="0 0 0"/> <geometry> <box size="0.05 0.05 0.05"/> </geometry> </collision> <visual> <origin xyz="0 0 0" rpy="0 0 0"/> <geometry> <box size="0.05 0.05 0.05"/> </geometry> <material name="red"/> </visual> <inertial> <mass value="1e-5" /> <origin xyz="0 0 0" rpy="0 0 0"/> <inertia ixx="1e-6" ixy="0" ixz="0" iyy="1e-6" iyz="0" izz="1e-6" /> </inertial> </link> <gazebo reference="camera_link"> <sensor type="camera" name="camera"> <update_rate>30.0</update_rate> <camera name="head"> <horizontal_fov>1.3962634</horizontal_fov> <image> <width>800</width> <height>800</height> <format>R8G8B8</format> </image> <clip> <near>0.02</near> <far>300</far> </clip> <noise> <type>gaussian</type> <mean>0.0</mean> <stddev>0.007</stddev> </noise> </camera> <plugin name="camera_controller" filename="libgazebo_ros_camera.so"> <alwaysOn>true</alwaysOn> <updateRate>0.0</updateRate> <cameraName>bot/camera</cameraName> <imageTopicName>image_raw</imageTopicName> <cameraInfoTopicName>camera_info</cameraInfoTopicName> <frameName>camera_link</frameName> <hackBaseline>0.07</hackBaseline> <distortionK1>0.0</distortionK1> <distortionK2>0.0</distortionK2> <distortionK3>0.0</distortionK3> <distortionT1>0.0</distortionT1> <distortionT2>0.0</distortionT2> </plugin> </sensor> </gazebo> </robot>

Ardupilot gazebo

Gazebo Plugin for Arducopter

  • ubuntu 16.04
  • ROS Kinetic
    • gazebo 7

Preinstall

sudo apt-get install libgazebo7-dev

Install and build plugin

cd <path>/ardupilot git clone https://github.com/SwiftGust/ardupilot_gazebo cd ardupilot_gazebo/ mkdir build cd build cmake .. make -j4 sudo make install

Setup

  • Add worlds to gazebo resource search path
  • Add modules to gazebo model search path (.bashrc)
#Add to .bashrc # init / export gazebo env variables source /usr/share/gazebo/setup.sh export GAZEBO_RESOURCE_PATH=/ardupilot_gazebo/gazebo_worlds:${GAZEBO_RESOURCE_PATH} #modules export GAZEBO_MODEL_PATH=~/ardupilot_gazebo/gazebo_models:${GAZEBO_MODEL_PATH} source ~/.bashrc

Run

  • Terminal 1 (SITL)
sim_vehicle.py -v ArduCopter -f gazebo-iris -m --mav10 --map --console -I0
  • v: Vehicle

  • f: Frame

  • m: mavproxy args

    • mav10
    • map
    • console
  • I:

  • Terminal 2 (gazebo)

gazebo --verbose iris_irlock_demo.world
[Dbg] [ArduCopterPlugin.cc:722] ArduCopter controller online detected.

Thursday, September 6, 2018

Gazebo and URDF model

source code

Catkin package

catkin_create_pkg demo_gazebo rospy cd demo_gazebo mkdir launch mkdir urdf

Minimal urdf file

The inertia matrix explained

<?xml version="1.0"?> <robot name="robot"> <link name="base_link"> <collision> <origin xyz="0 0 1" rpy="0 0 0"/> <geometry> <box size="2 2 2"/> </geometry> </collision> <visual> <origin xyz="0 0 1" rpy="0 0 0"/> <geometry> <box size="2 2 2"/> </geometry> <material name="orange"/> </visual> <inertial> <origin xyz="0 0 1" rpy="0 0 0"/> <mass value="1"/> <inertia ixx="1.0" ixy="0.0" ixz="0.0" iyy="1.0" iyz="0.0" izz="1.0"/> </inertial>> </link> </robot>

Spawn models

  • Using launch file
<launch> <param name="robot_description" textfile="$(find demo_gazebo)/urdf/robot_description.urdf" /> <include file="$(find gazebo_ros)/launch/empty_world.launch"/> <node name="spawn_urdf" pkg="gazebo_ros" type="spawn_model" args="-param robot_description -urdf -model my_robot" /> </launch>
  • Using rosrun
rosrun gazebo_ros spawn_model -file `rospack find demo_gazebo`/urdf/robot_description.urdf -urdf -z 1 -model my_robot

Gazebo services

  • Check if mode loaded
rosservice call /gazebo/get_world_properties sim_time: 1155.376 model_names: [ground_plane, my_robot] rendering_enabled: True success: True
  • Delete model
rosservice call /gazebo/delete_model "model_name: 'my_robot'" success: True status_message: "DeleteModel: successfully deleted model"

ROS python node

  • Call service to insert model into
#! /usr/bin/env python import rospy from gazebo_msgs.srv import SpawnModel from geometry_msgs.msg import Pose rospy.init_node('insert_object',log_level=rospy.INFO) initial_pose = Pose() initial_pose.position.x = 1 initial_pose.position.y = 1 initial_pose.position.z = 1 f = open('/home/user/simulation_ws/src/demo_gazebo/urdf/robot_description.urdf','r') urdff = f.read() rospy.wait_for_service('gazebo/spawn_urdf_model') spawn_model_proxy = rospy.ServiceProxy('gazebo/spawn_urdf_model', SpawnModel) spawn_model_proxy("some_robot_name", urdff, "robotos_name_space", initial_pose, "world")