-
Notifications
You must be signed in to change notification settings - Fork 14
Programmatic World Control
이 플러그인 예제는 프로그래밍 방식으로 중력을 수정한다.
Source: gazebo/examples/plugins/world_edit
이전 플러그인 튜코리얼에서 gazebo_plugin_tutorial
을 사용한다
$ mkdir ~/gazebo_plugin_tutorial; cd ~/gazebo_plugin_tutorial
파일 ~/gazebo_plugin_tutorial/world_edit.world
을 생성한다
$ gedit world_edit.world
아래 내용을 추가한다:
<?xml version ='1.0'?>
<sdf version ='1.4'>
<world name='default'>
<include>
<uri>model://ground_plane</uri>
</include>
<include>
<uri>model://sun</uri>
</include>
<plugin filename="libworld_edit.so" name="world_edit"/>
</world>
</sdf>
~/gazebo_plugin_tutorial/world_edit.cc
파일을 생성한다:
$ gedit world_edit.cc
아래 내용을 추가한다:
#include <sdf/sdf.hh>
#include <ignition/math/Pose3.hh>
#include "gazebo/gazebo.hh"
#include "gazebo/common/Plugin.hh"
#include "gazebo/msgs/msgs.hh"
#include "gazebo/physics/physics.hh"
#include "gazebo/transport/transport.hh"
/// \example examples/plugins/world_edit.cc
/// This example creates a WorldPlugin, initializes the Transport system by
/// creating a new Node, and publishes messages to alter gravity.
namespace gazebo
{
class WorldEdit : public WorldPlugin
{
public: void Load(physics::WorldPtr _parent, sdf::ElementPtr _sdf)
{
// Create a new transport node
transport::NodePtr node(new transport::Node());
// Initialize the node with the world name
node->Init(_parent->GetName());
// Create a publisher on the ~/physics topic
transport::PublisherPtr physicsPub =
node->Advertise<msgs::Physics>("~/physics");
msgs::Physics physicsMsg;
physicsMsg.set_type(msgs::Physics::ODE);
// Set the step time
physicsMsg.set_max_step_size(0.01);
// Change gravity
msgs::Set(physicsMsg.mutable_gravity(),
ignition::math::Vector3d(0.01, 0, 0.1));
physicsPub->Publish(physicsMsg);
}
};
// Register this plugin with the simulator
GZ_REGISTER_WORLD_PLUGIN(WorldEdit)
}
// Create a new transport node
transport::NodePtr node(new transport::Node());
// Initialize the node with the world name
node->Init(_parent->GetName());
새로운 노드포인터를 생성하고 world name을 사용하여 초기화한다. world name은 특정 world와 통신할 수 있게 한다.
// Create a publisher on the ~/physics topic
transport::PublisherPtr physicsPub =
node->Advertise<msgs::Physics>("~/physics");
"~/physics" topic에 메시지를 보내기 위해 publisher를 생성한다.
msgs::Physics physicsMsg;
physicsMsg.set_type(msgs::Physics::ODE);
// Set the step time
physicsMsg.set_max_step_size(0.01);
// Change gravity
msgs::Set(physicsMsg.mutable_gravity(),
ignition::math::Vector3d(0.01, 0, 0.1));
physicsPub->Publish(physicsMsg);
physics message가 생성되고 step time과 중력이 변경된다. 이 메시지는 "~/physics" topic로 게시된다(published).
Plugin Overview Tutorial을 한 사용자는, 위의 코드를 ~/gazebo_plugin_tutorial/world_edit.cc
로 저장하고 ~/gazebo_plugin_tutorial/CMakeLists.txt
파일에 아래 내용을 추가한다.
add_library(world_edit SHARED world_edit.cc)
target_link_libraries(world_edit ${GAZEBO_LIBRARIES})
컴파일을 하면 가제보시뮬레이션에 삽입할 수 있는 공유 라이브러리 ~/gazebo_plugin_tutorial/build/libworld_edit.so
가 생성된다
$ mkdir ~/gazebo_plugin_tutorial/build
$ cd ~/gazebo_plugin_tutorial/build
$ cmake ../
$ make
먼저 GAZEBO_PLUGIN_PATH
환경변수에 폴더를 추가해야한다.
export GAZEBO_PLUGIN_PATH=${GAZEBO_PLUGIN_PATH}:~/gazebo_plugin_tutorial/build/
그리고 터미널 창에 아래 내용을 입력한다.
$ cd ~/gazebo_plugin_tutorial
$ gazebo world_edit.world
그러면 비어있는 world를 볼 수 있다.
이제 렌더링 창 위에 있는 상자 아이콘을 사용하여 world에 박스를 추가한다. 상자가 카메라로부터 멀어져 올라가는 것을 볼 수 있다.
-
Robot Simulators
-
Build a Robot
- Model structure and requirements
- How to contribute a model
- Make a model
- Make a Mobile Robot
- The relationship among Link, Joint and Axis
- Import Meshes
- Attach Meshes
- Add a Sensor to a Robot
- Make a Simple Gripper
- Attach Gripper to Robot
- Nested model
- Model Editor
- Animated Box
- Make an animated model(actor)
- Inertial parameters of triangle meshes
- Visibility layers
-
Model Editor
-
Build a World
-
Tools and utilities
-
Write a plugin
-
Plugins
-
Sensors
-
User input
-
Transport Library
-
Rendering Library
-
Connect to ROS
-
Ros Control - Advanced
-
DRCSIM for ROS Kinetic (Ubuntu16.04)
-
DRCSIM
- DRC Simulator installation
- Launchfile options
- Spawn Atlas into a custom world
- Animate joints
- Atlas Keyboard Teleoperation over ROS
- Teleoperate atlas with a music mixer
- Visualization and logging
- Atlas MultiSense SL head
- How to use the Atlas Sim Interface
- Atlas fake walking
- Grasp with Sandia hands
- DRC vehicle tele-operation
- DRC vehicle tele operation with Atlas
- Sending joint commands with ROS
- Atlas control over ROS with python
- Modify environment
- Atlas switching control modes
- Atlas Controller Synchronization over ROS Topics
- Changing Viscous Damping Coefficients Over ROS Service
- Running BDI controller demo
- Using the RobotiQ 3 Finger Adaptive Robot Gripper
- BDI Atlas Robot Interface 3.0.0 Stand In Example
-
HAPTIX
- HAPTIX software install and update
- HAPTIX C API
- HAPTIX Matlab and Octave API
- HAPTIX Simulation World API
- HAPTIX Teleoperation
- HAPTIX environment setup
- HAPTIX Optitrack Control
- HAPTIX Tactor Glove
- HAPTIX Simulation World API with Custom World Example
- HAPTIX logging
- HAPTIX DEKA Luke hand installation
- HAPTIX Simulation Scoring Plugin Example
-
MoveIt!
-
Rviz & rqt & ROSBAG
- Control Theory
- TroubleShooting
- Solidworks model to URDF
- ROS-Gazebo with MATLab
- MATLab installation in Linux
- [Gazebo simulation with MATLab]