반응형
Installation Guide
http://philserver.bplaced.net/fbe/download.php
FlexBE Behavior Engine
Download FlexBE Downloading and installing FlexBE can be completed in just a few steps, assuming that you already have ROS installed. The engine itself is both available as binary installation on the ROS build server and as source code on github. You can g
philserver.bplaced.net
catkin build 실행 결과
정상적으로 빌드된 것을 알 수 있다

System Configuration
roslaunch flexbe_app flexbe_full.launch

Tutorial) init pose 지정하기
다음과 같이 인터페이스를 설정한다음 "Test"라는 state를 만들었다


코드는 아래와 같다
#!/usr/bin/env python
import rospy
from flexbe_core import EventState, Logger
from flexbe_core.proxy import ProxyPublisher
from geometry_msgs.msg import PoseWithCovarianceStamped
from tf import transformations
from geometry_msgs.msg import Pose, Point, Quaternion
class SetInitialPoseState(EventState):
"""
A state to set the initial pose of a robot in the map frame.
-- x float Initial x-coordinate.
-- y float Initial y-coordinate.
-- orientation float Initial orientation in radians.
#> succeeded bo
pub_initial_pose = ProxyPublisher({"/initialpose": PoseWithCovarianceStamped})ol True if the initial pose has been set successfully.
"""
def __init__(self):
"""Constructor of the state."""
super(SetInitialPoseState, self).__init__(outcomes=['succeeded'], input_keys=['initial_pose'])
self.pub_initial_pose = ProxyPublisher({"/initialpose": PoseWithCovarianceStamped})
self.succeeded = False
def execute(self, userdata):
"""Execution of the state."""
if self.succeeded:
return 'succeeded'
def on_enter(self, userdata):
self.succeeded = False
initial_pose_msg = PoseWithCovarianceStamped()
initial_pose_msg.header.frame_id = "map"
initial_pose_msg.header.stamp = rospy.Time.now()
initial_pose_msg.pose.pose.position.x = userdata.initial_pose[0]
initial_pose_msg.pose.pose.position.y = userdata.initial_pose[1]
qt = transformations.quaternion_from_euler(0, 0, userdata.initial_pose[2])
initial_pose_msg.pose.pose.orientation = Quaternion(*qt)
self.pub_initial_pose.publish("/initialpose", initial_pose_msg)
Logger.loginfo("Initial pose set to ({}, {}) with orientation ({})".format(userdata.initial_pose[0], userdata.initial_pose[1], userdata.initial_pose[2]))
self.succeeded = True
def on_exit(self, userdata):
pass
def on_start(self):
pass
def on_stop(self):
pass
Result
반응형
'Robotics 🤖 > flexbe' 카테고리의 다른 글
[FlexBE] FlexBE navigation 공부하기(feat. CHRISLab github) (2) | 2023.09.17 |
---|---|
[FlexBE] Flexbe란? Flexbe에 대하여 (ROS Wiki) (0) | 2023.09.17 |