Skip to content

Commit

Permalink
Merge pull request #3 from AscendNTNU/request_recipe
Browse files Browse the repository at this point in the history
feat: service to request item recipe
  • Loading branch information
Baardrw authored Oct 4, 2023
2 parents 4f3bdb3 + 6e91d26 commit 2d4a7f7
Show file tree
Hide file tree
Showing 5 changed files with 168 additions and 44 deletions.
10 changes: 10 additions & 0 deletions docs/crafting.md
Original file line number Diff line number Diff line change
Expand Up @@ -8,5 +8,15 @@ call `/mineros/interaction/craft` with a `mineros_inter/Craft` request. The requ
returns:
- `bool success` - Whether the operation was successful or not

# Request item
call `/mineros/interaction/request` with a `mineros_inter/Request` request. The request has the following params:
- `mineros_inter/Item` - item to request
- `bool crafting_table` - if the bot should use a crafting table or not
- `geometry_msgs/Pose crafting_table_location` - The location of the crafting table to use, needs only be specified if crafting_table is true

returns:
- `bool success` - Whether the operation was successful or not
- `mineros_inter/Recipe[]` - The recipes it found

## Note on internals
Internally mineflayer looks up the recipe of the item and checks if the bot has the items required to craft it, if it does it crafts if not it returns false.
106 changes: 71 additions & 35 deletions src/mineros/mineros/main.py
Original file line number Diff line number Diff line change
Expand Up @@ -11,10 +11,10 @@

from std_msgs.msg import Empty
from geometry_msgs.msg import PoseStamped, PoseArray, Pose, Point
from mineros_inter.srv import FindBlocks, MineBlock, Inventory, PlaceBlock, Craft, BlockInfo, FurnaceInfo, FurnaceUpdate
from mineros_inter.srv import FindBlocks, MineBlock, Inventory, PlaceBlock, Craft, BlockInfo, FurnaceInfo, FurnaceUpdate, Recipe
from mineros_inter.msg import Item, BlockPose, Furnace

from .utils import item_to_item_msg, item_equal
from .utils import item_to_item_msg, item_equal, recipe_to_recipe_msg

mineflayer = require('mineflayer')
pathfinder = require('mineflayer-pathfinder')
Expand Down Expand Up @@ -44,6 +44,8 @@
is to bussy wait on falgs, the below events set the flags whenever a new event is completed
"""
goal_reached = False


@On(bot, 'goal_reached')
def on_goal_reached(_, goal):
print(f'Goal reached')
Expand All @@ -53,6 +55,8 @@ def on_goal_reached(_, goal):


digging_completed = False


@On(bot, 'diggingCompleted')
def on_digging_completed(_, block):
global digging_completed
Expand Down Expand Up @@ -93,7 +97,7 @@ def __init__(self):
self.set_position_callback,
10
)

self.set_look_at_block = self.create_subscription(
PoseStamped,
'/mineros/set_look_at_block',
Expand Down Expand Up @@ -146,12 +150,18 @@ def __init__(self):
self.craft_item_service_callback
)

self.get_recipe_service = self.create_service(
Recipe,
'/mineros/interaction/recipe',
self.get_recipe_service_callback
)

self.furnace_info_service = self.create_service(
FurnaceInfo,
'/mineros/interaction/furnace_info',
self.furnace_info_service_callback
)

self.furnace_update_service = self.create_service(
FurnaceUpdate,
'/mineros/interaction/furnace_update',
Expand Down Expand Up @@ -198,8 +208,7 @@ def spin_for_digging(self, block):
self.get_logger().info("Digging timeout")
return
digging_completed = False



def calculate_wait_time(self, target: Vec3):
"""Calculates the time it takes to get to a target position on average"""
current_position = bot.entity.position
Expand Down Expand Up @@ -267,19 +276,20 @@ def set_position_callback(self, msg: PoseStamped):
# Wait for goal to be reached
self.spin_for_goal()
self.position_reached_publisher.publish(Empty())

def look_at_block_callback(self, msg: PoseStamped):
self.get_logger().info(f"Look at block")
bot.pathfinder.setGoal(None)
vec = Vec3(msg.pose.position.x, msg.pose.position.y, msg.pose.position.z)
vec = Vec3(msg.pose.position.x,
msg.pose.position.y, msg.pose.position.z)
block = bot.blockAt(vec)

goal = pathfinder.goals.GoalLookAtBlock(block.position, bot.world)
bot.pathfinder.setGoal(goal)

self.spin_for_goal()
self.position_reached_publisher.publish(Empty())

def set_position_composite_callback(self, msg: PoseArray):
self.get_logger().info(f"Set position composite")

Expand Down Expand Up @@ -437,33 +447,56 @@ def craft_item_service_callback(self, request: Craft.Request, response: Craft.Re

return response

def get_recipe_service_callback(self, request: Recipe.Request, response: Recipe.Response):
item = request.item
self.get_logger().info(f"Getting recipe for item: {item.id}")

if request.crafting_table:
crafting_table = bot.blockAt(Vec3(
request.crafting_table_location.position.x, request.crafting_table_location.position.y, request.crafting_table_location.position.z))
else:
crafting_table = None

recipe = list(bot.recipesAll(item.id, None, crafting_table))

returned_recipes = []
for r in recipe:
recipe_msg = recipe_to_recipe_msg(r)
self.get_logger().info(f"Recipe: {recipe_msg}")
returned_recipes.append(recipe_msg)

response.recipes = returned_recipes
response.success = len(recipe) > 0
return response

def furnace_info_service_callback(self, request: FurnaceInfo.Request, response: FurnaceInfo.Response):
self.get_logger().info(f"Furnace info called")
furnace_block_point: Point = request.block_pose.position
furnace_msg: Furnace = Furnace()

furnace_block = bot.blockAt(Vec3(
furnace_block_point.x, furnace_block_point.y, furnace_block_point.z))

if furnace_block is None:
self.get_logger().info(f"Can't find furnace")
response.success = False
return response
elif furnace_block.type != registry.blocksByName.furnace.id:
self.get_logger().info(f'{furnace_block.type}, {registry.blocksByName.furnace.type}')
self.get_logger().info(f"Given block is not a furnace, it is {furnace_block.name}")
self.get_logger().info(
f'{furnace_block.type}, {registry.blocksByName.furnace.type}')
self.get_logger().info(
f"Given block is not a furnace, it is {furnace_block.name}")
response.success = False
return response

furnace = None
furnace = bot.openFurnace(furnace_block)

if furnace is None:
self.get_logger().info(f"Can't find furnace")
response.success = False
return response



furnace_msg.input_item = item_to_item_msg(furnace.inputItem())
furnace_msg.fuel_item = item_to_item_msg(furnace.fuelItem())
furnace_msg.output_item = item_to_item_msg(furnace.outputItem())
Expand All @@ -472,48 +505,51 @@ def furnace_info_service_callback(self, request: FurnaceInfo.Request, response:
else:
furnace_msg.progress = 0.0

self.get_logger().info(f'{furnace_msg}')

response.furnace = furnace_msg
response.success = True
return response

def furnace_update_service_callback(self, request: FurnaceUpdate.Request, response: FurnaceUpdate.Response):
def evaluate_furnace_action(request_item, old_item, take_action: callable, put_action: callable):
if request_item is not None and not item_equal(old_item, request_item):
if old_item.count > 0:
take_action()
if request_item.count > 0:
put_action(request_item.id, None, request_item.count)

furnace_info = FurnaceInfo.Request()
furnace_info.block_pose = request.block_pose

old_furnace = self.furnace_info_service_callback(furnace_info, FurnaceInfo.Response())

old_furnace = self.furnace_info_service_callback(
furnace_info, FurnaceInfo.Response())
if not old_furnace.success:
response.success = False
return response

furnace_block_point: Point = request.block_pose.position
furnace_block = bot.blockAt(Vec3(
furnace_block_point.x, furnace_block_point.y, furnace_block_point.z))
furnace = bot.openFurnace(furnace_block)
furnace = bot.openFurnace(furnace_block)

if furnace is None:
self.get_logger().info(f"Can't find furnace")
response.success = False
return response

evaluate_furnace_action(request.furnace.input_item, old_furnace.furnace.input_item, furnace.takeInput, furnace.putInput)
evaluate_furnace_action(request.furnace.output_item, old_furnace.furnace.output_item, furnace.takeOutput, furnace.putOutput)

evaluate_furnace_action(
request.furnace.input_item, old_furnace.furnace.input_item, furnace.takeInput, furnace.putInput)
evaluate_furnace_action(request.furnace.output_item,
old_furnace.furnace.output_item, furnace.takeOutput, furnace.putOutput)
if not request.ignore_fuel:
evaluate_furnace_action(request.furnace.fuel_item, old_furnace.furnace.fuel_item, furnace.takeFuel, furnace.putFuel)

evaluate_furnace_action(
request.furnace.fuel_item, old_furnace.furnace.fuel_item, furnace.takeFuel, furnace.putFuel)

# Now the furnace should be equal to the update furnace request version, is good.
response.success = True
return response





# TODO kill or avoid mobs

def local_pose_timer_callback(self):
Expand Down
45 changes: 41 additions & 4 deletions src/mineros/mineros/utils.py
Original file line number Diff line number Diff line change
@@ -1,4 +1,41 @@
from mineros_inter.msg import Item, Furnace
from mineros_inter.msg import Item, Furnace, Recipe


def recipe_to_recipe_msg(recipe) -> Recipe:
def recipe_item_to_item_msg(item) -> Item:
if item is None:
item_msg = Item()
item_msg.id = 0
item_msg.count = 0
item_msg.metadata = 0
return item_msg

item_msg = Item()
item_msg.id = int(item.id)
item_msg.count = int(item.count)
item_msg.metadata = 0
return item_msg

recipe_msg = Recipe()
recipe_msg.output_item = recipe_item_to_item_msg(recipe.result)

recipe_msg.input_items = []
items = []
items_in_shape = [items.extend(row) for row in recipe.inShape]
item_ids = list(map(lambda item: item.id, items))
unique_item_ids = set(item_ids)

for unique_item_id in unique_item_ids:
if unique_item_id == -1:
continue
item_msg = Item()
item_msg.id = int(unique_item_id)
item_msg.count = item_ids.count(unique_item_id)
item_msg.metadata = 0
recipe_msg.input_items.append(item_msg)

return recipe_msg


def item_to_item_msg(item) -> Item:
if item is None:
Expand All @@ -8,19 +45,19 @@ def item_to_item_msg(item) -> Item:
item_msg.slot = 0
item_msg.metadata = 0
return item_msg

item_msg = Item()
item_msg.id = item.type
item_msg.count = item.count
item_msg.slot = item.slot
item_msg.metadata = item.metadata
return item_msg


def item_equal(item1: Item, item2: Item):

if item1 is None and item2 is None:
return True
if item1 is None or item2 is None:
return False
return item1.id == item2.id and item1.count == item2.count

2 changes: 1 addition & 1 deletion src/mineros_interface
49 changes: 45 additions & 4 deletions src/mineros_testing/mineros_testing/interaction_test.py
Original file line number Diff line number Diff line change
@@ -1,9 +1,10 @@
import rclpy
from rclpy.node import Node
from typing import List, Tuple

from geometry_msgs.msg import PoseStamped, Pose

from mineros_inter.srv import FindBlocks, FurnaceInfo, FurnaceUpdate
from mineros_inter.srv import FindBlocks, FurnaceInfo, FurnaceUpdate, Recipe
from mineros_inter.msg import Furnace, Item

from .utils import item_equal
Expand Down Expand Up @@ -37,6 +38,16 @@ def __init__(self):
'/mineros/interaction/furnace_update',
)

self.get_recipe_client = self.create_client(
Recipe,
'/mineros/interaction/recipe',
)

self.find_block_client = self.create_client(
FindBlocks,
'/mineros/mining/find_blocks',
)

self.furnace_loc = (754.452, 102.0, 1666.395)

self.tests()
Expand All @@ -45,11 +56,30 @@ def position_cb(self, msg: PoseStamped):
self.position = msg

def tests(self):
self.test_furnace_info()
self.test_update_furnace()
# self.test_furnace_info()
# self.test_update_furnace()
self.test_get_recipe()

self.destroy_node()
rclpy.shutdown()

def test_get_recipe(self):
req = Recipe.Request()

diamond_pickaxe = Item()
diamond_pickaxe.id = 799
diamond_pickaxe.count = 1
req.item = diamond_pickaxe

crafting_table_loc = self.find_blocks(182, 1)[0]
assert crafting_table_loc is not None
req.crafting_table_location = crafting_table_loc
req.crafting_table = True

future = self.get_recipe_client.call_async(req)
rclpy.spin_until_future_complete(self, future)
self.get_logger().info(f'{future.result()}')


def test_furnace_info(self):
self.get_logger().info('Testing furnace info')
Expand Down Expand Up @@ -94,7 +124,18 @@ def test_update_furnace(self):
new: Furnace = self.test_furnace_info()
assert item_equal(new.fuel_item, req.furnace.fuel_item)


def find_blocks(self, blockid: int, count: int) -> List[Pose]:
self.get_logger().info('Find blocks')
block_search = FindBlocks.Request()
block_search.blockid = blockid
block_search.count = count

while not self.find_block_client.wait_for_service(timeout_sec=1.0):
self.get_logger().info('Waiting for service')
future = self.find_block_client.call_async(block_search)
rclpy.spin_until_future_complete(self, future)
blocks = future.result()
return blocks.blocks.poses

def main(args=None):
rclpy.init(args=args)
Expand Down

0 comments on commit 2d4a7f7

Please sign in to comment.