Skip to content

Commit

Permalink
[gpt4v_vqa] add token and quota calculation
Browse files Browse the repository at this point in the history
  • Loading branch information
sktometometo committed Jan 9, 2024
1 parent 8c3ecde commit ff9d5c0
Showing 1 changed file with 9 additions and 6 deletions.
15 changes: 9 additions & 6 deletions gpt4v_vqa/node_scripts/gpt4v_vqa_node.py
Original file line number Diff line number Diff line change
Expand Up @@ -10,16 +10,15 @@
import ros_numpy
import rospy
from dynamic_reconfigure.server import Server
from jsk_recognition_msgs.msg import (
QuestionAndAnswerText,
VQATaskAction,
VQATaskGoal,
VQATaskResult,
)
from jsk_recognition_msgs.msg import (QuestionAndAnswerText, VQATaskAction,
VQATaskGoal, VQATaskResult)
from sensor_msgs.msg import Image

from gpt4v_vqa.cfg import GPT4VConfig

COST_PER_TOKEN_FOR_INPUT = 0.01 / 1000
COST_PER_TOKEN_FOR_OUTPUT = 0.03 / 1000


class GPT4VClientNode(object):
def __init__(self, api_key: str):
Expand Down Expand Up @@ -113,6 +112,10 @@ def _ac_cb(self, goal: VQATaskGoal):
result.result.result.append(
QuestionAndAnswerText(question=question, answer=answer)
)
input_tokens = response["usage"]["prompt_tokens"]
output_tokens = response["usage"]["completion_tokens"]
rospy.loginfo(f"Used tokens for this completion is {input_tokens} for input and {output_tokens} for output.")
rospy.loginfo(f"Which costs ${input_tokens * COST_PER_TOKEN_FOR_INPUT} USD for input and ${output_tokens * COST_PER_TOKEN_FOR_OUTPUT} USD for output.")
if len(result.result.result) == 0:
rospy.logerr("No answers found")
self.ac.set_aborted(result)
Expand Down

0 comments on commit ff9d5c0

Please sign in to comment.