Skip to content

Commit

Permalink
Fix existing style issues (#252)
Browse files Browse the repository at this point in the history
Signed-off-by: Luca Della Vedova <lucadv@intrinsic.ai>
  • Loading branch information
luca-della-vedova authored Jul 24, 2024
1 parent 7ecd917 commit 3daa9ec
Show file tree
Hide file tree
Showing 2 changed files with 42 additions and 43 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -39,10 +39,10 @@
import rmf_adapter.vehicletraits as traits
from rmf_fleet_msgs.msg import DockSummary
from rmf_fleet_msgs.msg import Location
from rmf_fleet_msgs.msg import ModeRequest
from rmf_fleet_msgs.msg import PathRequest
from rmf_fleet_msgs.msg import RobotMode
from rmf_fleet_msgs.msg import RobotState
from rmf_fleet_msgs.msg import ModeRequest
import socketio
import uvicorn
import yaml
Expand Down Expand Up @@ -406,13 +406,13 @@ async def toggle_attach(robot_name: str, cmd_id: int, mode: Request):
# Toggle action mode
if mode.toggle:
# Use robot mode publisher to set it to "attaching cart mode"
self.get_logger().info(f'Publishing attaching mode...')
self.get_logger().info('Publishing attaching mode...')
msg = self._make_mode_request(robot_name, cmd_id,
RobotMode.MODE_PERFORMING_ACTION,
'attach_cart')
else:
# Use robot mode publisher to set it to "detaching cart mode"
self.get_logger().info(f'Publishing detaching mode...')
self.get_logger().info('Publishing detaching mode...')
msg = self._make_mode_request(robot_name, cmd_id,
RobotMode.MODE_PERFORMING_ACTION,
'detach_cart')
Expand Down
79 changes: 39 additions & 40 deletions rmf_demos_tasks/rmf_demos_tasks/dispatch_cart_delivery.py
Original file line number Diff line number Diff line change
Expand Up @@ -14,19 +14,18 @@
# See the License for the specific language governing permissions and
# limitations under the License.

import sys
import uuid
import argparse
import json
import asyncio
import json
import sys
import uuid

import rclpy
from rclpy.node import Node
from rclpy.parameter import Parameter
from rclpy.qos import qos_profile_system_default
from rclpy.qos import QoSProfile
from rclpy.qos import QoSHistoryPolicy as History
from rclpy.qos import QoSDurabilityPolicy as Durability
from rclpy.qos import QoSHistoryPolicy as History
from rclpy.qos import QoSProfile
from rclpy.qos import QoSReliabilityPolicy as Reliability

from rmf_task_msgs.msg import ApiRequest, ApiResponse
Expand All @@ -41,10 +40,10 @@ def __init__(self, argv=sys.argv):
parser = argparse.ArgumentParser()
parser.add_argument('-p', '--pickup', required=True,
type=str,
help="Pickup waypoint name")
help='Pickup waypoint name')
parser.add_argument('-d', '--dropoff', required=True,
type=str,
help="Dropoff waypoint name")
help='Dropoff waypoint name')
parser.add_argument('-F', '--fleet', type=str,
help='Fleet name, should define tgt with robot')
parser.add_argument('-R', '--robot', type=str,
Expand All @@ -55,7 +54,7 @@ def __init__(self, argv=sys.argv):
parser.add_argument('-pt', '--priority',
help='Priority value for this request',
type=int, default=0)
parser.add_argument("--use_sim_time", action="store_true",
parser.add_argument('--use_sim_time', action='store_true',
help='Use sim time, default: false')

self.args = parser.parse_args(argv[1:])
Expand All @@ -72,75 +71,75 @@ def __init__(self, argv=sys.argv):

# enable ros sim time
if self.args.use_sim_time:
self.get_logger().info("Using Sim Time")
param = Parameter("use_sim_time", Parameter.Type.BOOL, True)
self.get_logger().info('Using Sim Time')
param = Parameter('use_sim_time', Parameter.Type.BOOL, True)
self.set_parameters([param])

# Construct task
msg = ApiRequest()
msg.request_id = "delivery_" + str(uuid.uuid4())
msg.request_id = 'delivery_' + str(uuid.uuid4())
payload = {}
if self.args.fleet and self.args.robot:
self.get_logger().info("Using 'robot_task_request'")
payload["type"] = "robot_task_request"
payload["robot"] = self.args.robot
payload["fleet"] = self.args.fleet
payload['type'] = 'robot_task_request'
payload['robot'] = self.args.robot
payload['fleet'] = self.args.fleet
else:
self.get_logger().info("Using 'dispatch_task_request'")
payload["type"] = "dispatch_task_request"
payload['type'] = 'dispatch_task_request'
request = {}

# Set task request start time
now = self.get_clock().now().to_msg()
now.sec = now.sec + self.args.start_time
start_time = now.sec * 1000 + round(now.nanosec/10**6)
request["unix_millis_earliest_start_time"] = start_time
request['unix_millis_earliest_start_time'] = start_time

# TODO(luca) expose duration and tool sink to CLI
def __create_perform_action(action_category, duration_ms=10000,
use_tool_sink=False):
return {
"unix_millis_action_duration_estimate": duration_ms,
'unix_millis_action_duration_estimate': duration_ms,
# for internal FleetUpdateHandle to check if action
# is performable by this fleet
"category": action_category,
"description":
'category': action_category,
'description':
{
# for fleet manager to start action process
"deliver_cart_task_name": action_category
'deliver_cart_task_name': action_category
},
"use_tool_sink": use_tool_sink
'use_tool_sink': use_tool_sink
}

# Define with request category compose
request["category"] = "compose"
request['category'] = 'compose'

# Define task request description with phases
description = {} # task_description_Compose.json
description["category"] = "deliver_cart"
description["phases"] = []
description['category'] = 'deliver_cart'
description['phases'] = []
activities = []
# Add each phase
activities.append({
"category": "go_to_place",
"description": self.args.pickup})
'category': 'go_to_place',
'description': self.args.pickup})
activities.append({
"category": "perform_action",
"description": __create_perform_action("delivery_pickup")})
'category': 'perform_action',
'description': __create_perform_action('delivery_pickup')})
activities.append({
"category": "go_to_place",
"description": self.args.dropoff})
'category': 'go_to_place',
'description': self.args.dropoff})
activities.append({
"category": "perform_action",
"description": __create_perform_action("delivery_dropoff")})
'category': 'perform_action',
'description': __create_perform_action('delivery_dropoff')})
# Add activities to phases
description["phases"].append(
{"activity": {
"category": "sequence",
"description": {"activities": activities}}})
description['phases'].append(
{'activity': {
'category': 'sequence',
'description': {'activities': activities}}})

request["description"] = description
payload["request"] = request
request['description'] = description
payload['request'] = request
msg.json_msg = json.dumps(payload)

def receive_response(response_msg: ApiResponse):
Expand All @@ -151,7 +150,7 @@ def receive_response(response_msg: ApiResponse):
ApiResponse, 'task_api_responses', receive_response, 10
)

print(f"Json msg payload: \n{json.dumps(payload, indent=2)}")
print(f'Json msg payload: \n{json.dumps(payload, indent=2)}')

self.pub.publish(msg)

Expand Down

0 comments on commit 3daa9ec

Please sign in to comment.