このリポジトリは、llama.cpp を ROS 2 に統合するための ROS 2 パッケージのセットを提供します。 llama_ros パッケージを使用すると、GGUF ベースの LLM および VLM を実行して、llama.cpp の強力な最適化機能を ROS 2 プロジェクトに簡単に組み込むことができます。 GBNF 文法などの llama.cpp の機能を使用して、リアルタイムで LoRA を変更することもできます。
CUDA で llama_ros を実行するには、まず CUDA Toolkit をインストールする必要があります。次に、 --cmake-args -DGGML_CUDA=ON
を指定して llama_ros をコンパイルし、CUDA サポートを有効にします。
cd ~ /ros2_ws/src
git clone https://github.com/mgonzs13/llama_ros.git
pip3 install -r llama_ros/requirements.txt
cd ~ /ros2_ws
rosdep install --from-paths src --ignore-src -r -y
colcon build --cmake-args -DGGML_CUDA=ON # add this for CUDA
llama_ros Docker をビルドするか、DockerHub からイメージをダウンロードします。 CUDA ( USE_CUDA
) を使用して llama_ros をビルドすることを選択し、CUDA バージョン ( CUDA_VERSION
) を選択できます。イメージをビルドするときに、 DOCKER_BUILDKIT=0
使用して CUDA で llama_ros をコンパイルする必要があることに注意してください。
DOCKER_BUILDKIT=0 docker build -t llama_ros --build-arg USE_CUDA=1 --build-arg CUDA_VERSION=12-6 .
Docker コンテナを実行します。 CUDA を使用する場合は、NVIDIA Container Tollkit をインストールし、 --gpus all
追加する必要があります。
docker run -it --rm --gpus all llama_ros
llama_ros には、ROS 2 エコシステム内の GGUF ベースの LLM のテストを高速化するコマンドが含まれています。このようにして、次のコマンドが ROS 2 コマンドに統合されます。
このコマンドを使用すると、YAML ファイルから LLM を起動します。 YAML の構成は、通常の起動ファイルを使用するのと同じ方法で LLM を起動するために使用されます。これを使用する方法の例を次に示します。
ros2 llama launch ~ /ros2_ws/src/llama_ros/llama_bringup/models/StableLM-Zephyr.yaml
このコマンドを使用すると、起動された LLM にプロンプトが送信されます。このコマンドは、プロンプトである文字列を使用し、次の引数を持ちます。
-r
、 --reset
): プロンプトを表示する前に LLM をリセットするかどうか-t
、 --temp
): 温度値--image-url
): VLM に送信する画像 URLこれを使用する方法の例を次に示します。
ros2 llama prompt " Do you know ROS 2? " -t 0.0
まず、llama_ros または llava_ros を使用するための起動ファイルを作成する必要があります。この起動ファイルには、HuggingFace からモデルをダウンロードして構成するための主要なパラメーターが含まれています。次の例と事前定義された起動ファイルを見てください。
from launch import LaunchDescription
from llama_bringup . utils import create_llama_launch
def generate_launch_description ():
return LaunchDescription ([
create_llama_launch (
n_ctx = 2048 , # context of the LLM in tokens
n_batch = 8 , # batch size in tokens
n_gpu_layers = 0 , # layers to load in GPU
n_threads = 1 , # threads
n_predict = 2048 , # max tokens, -1 == inf
model_repo = "TheBloke/Marcoroni-7B-v3-GGUF" , # Hugging Face repo
model_filename = "marcoroni-7b-v3.Q4_K_M.gguf" , # model file in repo
system_prompt_type = "Alpaca" # system prompt type
)
])
ros2 launch llama_bringup marcoroni.launch.py
n_ctx : 2048 # context of the LLM in tokens
n_batch : 8 # batch size in tokens
n_gpu_layers : 0 # layers to load in GPU
n_threads : 1 # threads
n_predict : 2048 # max tokens, -1 == inf
model_repo : " cstr/Spaetzle-v60-7b-GGUF " # Hugging Face repo
model_filename : " Spaetzle-v60-7b-q4-k-m.gguf " # model file in repo
system_prompt_type : " Alpaca " # system prompt type
import os
from launch import LaunchDescription
from llama_bringup . utils import create_llama_launch_from_yaml
from ament_index_python . packages import get_package_share_directory
def generate_launch_description ():
return LaunchDescription ([
create_llama_launch_from_yaml ( os . path . join (
get_package_share_directory ( "llama_bringup" ), "models" , "Spaetzle.yaml" ))
])
ros2 launch llama_bringup spaetzle.launch.py
n_ctx : 2048 # context of the LLM in tokens
n_batch : 8 # batch size in tokens
n_gpu_layers : 0 # layers to load in GPU
n_threads : 1 # threads
n_predict : 2048 # max tokens, -1 == inf
model_repo : " Qwen/Qwen2.5-Coder-7B-Instruct-GGUF " # Hugging Face repo
model_filename : " qwen2.5-coder-7b-instruct-q4_k_m-00001-of-00002.gguf " # model shard file in repo
system_prompt_type : " ChatML " # system prompt type
ros2 llama launch Qwen2.yaml
from launch import LaunchDescription
from llama_bringup . utils import create_llama_launch
def generate_launch_description ():
return LaunchDescription ([
create_llama_launch (
use_llava = True , # enable llava
n_ctx = 8192 , # context of the LLM in tokens, use a huge context size to load images
n_batch = 512 , # batch size in tokens
n_gpu_layers = 33 , # layers to load in GPU
n_threads = 1 , # threads
n_predict = 8192 , # max tokens, -1 == inf
model_repo = "cjpais/llava-1.6-mistral-7b-gguf" , # Hugging Face repo
model_filename = "llava-v1.6-mistral-7b.Q4_K_M.gguf" , # model file in repo
mmproj_repo = "cjpais/llava-1.6-mistral-7b-gguf" , # Hugging Face repo
mmproj_filename = "mmproj-model-f16.gguf" , # mmproj file in repo
system_prompt_type = "Mistral" # system prompt type
)
])
ros2 launch llama_bringup llava.launch.py
use_llava : True # enable llava
n_ctx : 8192 # context of the LLM in tokens use a huge context size to load images
n_batch : 512 # batch size in tokens
n_gpu_layers : 33 # layers to load in GPU
n_threads : 1 # threads
n_predict : 8192 # max tokens -1 : : inf
model_repo : " cjpais/llava-1.6-mistral-7b-gguf " # Hugging Face repo
model_filename : " llava-v1.6-mistral-7b.Q4_K_M.gguf " # model file in repo
mmproj_repo : " cjpais/llava-1.6-mistral-7b-gguf " # Hugging Face repo
mmproj_filename : " mmproj-model-f16.gguf " # mmproj file in repo
system_prompt_type : " mistral " # system prompt type
def generate_launch_description ():
return LaunchDescription ([
create_llama_launch_from_yaml ( os . path . join (
get_package_share_directory ( "llama_bringup" ),
"models" , "llava-1.6-mistral-7b-gguf.yaml" ))
])
ros2 launch llama_bringup llava.launch.py
LLM を起動するときに LoRA アダプターを使用できます。 llama.cpp 機能を使用すると、各アダプターに適用するスケールを選択して複数のアダプターをロードできます。ここでは、Phi-3 で LoRA アダプターを使用する例を示します。 /llama/list_loras
サービスを使用して LoRA をリストし、 /llama/update_loras
サービスを使用してスケール値を変更できます。スケール値 0.0 は、その LoRA を使用しないことを意味します。
n_ctx : 2048
n_batch : 8
n_gpu_layers : 0
n_threads : 1
n_predict : 2048
model_repo : " bartowski/Phi-3.5-mini-instruct-GGUF "
model_filename : " Phi-3.5-mini-instruct-Q4_K_M.gguf "
lora_adapters :
- repo : " zhhan/adapter-Phi-3-mini-4k-instruct_code_writing "
filename : " Phi-3-mini-4k-instruct-adaptor-f16-code_writer.gguf "
scale : 0.5
- repo : " zhhan/adapter-Phi-3-mini-4k-instruct_summarization "
filename : " Phi-3-mini-4k-instruct-adaptor-f16-summarization.gguf "
scale : 0.5
system_prompt_type : " Phi-3 "
llama_ros と llava_ros は両方とも、モデルの主な機能にアクセスするための ROS 2 インターフェイスを提供します。ここでは、ROS 2 ノード内でそれらを使用する方法の例をいくつか示します。さらに、llama_demo_node.py および llava_demo_node.py のデモを見てください。
from rclpy . node import Node
from llama_msgs . srv import Tokenize
class ExampleNode ( Node ):
def __init__ ( self ) -> None :
super (). __init__ ( "example_node" )
# create the client
self . srv_client = self . create_client ( Tokenize , "/llama/tokenize" )
# create the request
req = Tokenize . Request ()
req . text = "Example text"
# call the tokenize service
self . srv_client . wait_for_service ()
tokens = self . srv_client . call ( req ). tokens
from rclpy . node import Node
from llama_msgs . srv import Detokenize
class ExampleNode ( Node ):
def __init__ ( self ) -> None :
super (). __init__ ( "example_node" )
# create the client
self . srv_client = self . create_client ( Detokenize , "/llama/detokenize" )
# create the request
req = Detokenize . Request ()
req . tokens = [ 123 , 123 ]
# call the tokenize service
self . srv_client . wait_for_service ()
text = self . srv_client . call ( req ). text
LLM で埋め込みを生成できるように、埋め込みを true に設定して llama_ros を起動することを忘れないでください。
from rclpy . node import Node
from llama_msgs . srv import Embeddings
class ExampleNode ( Node ):
def __init__ ( self ) -> None :
super (). __init__ ( "example_node" )
# create the client
self . srv_client = self . create_client ( Embeddings , "/llama/generate_embeddings" )
# create the request
req = Embeddings . Request ()
req . prompt = "Example text"
req . normalize = True
# call the embedding service
self . srv_client . wait_for_service ()
embeddings = self . srv_client . call ( req ). embeddings
import rclpy
from rclpy . node import Node
from rclpy . action import ActionClient
from llama_msgs . action import GenerateResponse
class ExampleNode ( Node ):
def __init__ ( self ) -> None :
super (). __init__ ( "example_node" )
# create the client
self . action_client = ActionClient (
self , GenerateResponse , "/llama/generate_response" )
# create the goal and set the sampling config
goal = GenerateResponse . Goal ()
goal . prompt = self . prompt
goal . sampling_config . temp = 0.2
# wait for the server and send the goal
self . action_client . wait_for_server ()
send_goal_future = self . action_client . send_goal_async (
goal )
# wait for the server
rclpy . spin_until_future_complete ( self , send_goal_future )
get_result_future = send_goal_future . result (). get_result_async ()
# wait again and take the result
rclpy . spin_until_future_complete ( self , get_result_future )
result : GenerateResponse . Result = get_result_future . result (). result
import cv2
from cv_bridge import CvBridge
import rclpy
from rclpy . node import Node
from rclpy . action import ActionClient
from llama_msgs . action import GenerateResponse
class ExampleNode ( Node ):
def __init__ ( self ) -> None :
super (). __init__ ( "example_node" )
# create a cv bridge for the image
self . cv_bridge = CvBridge ()
# create the client
self . action_client = ActionClient (
self , GenerateResponse , "/llama/generate_response" )
# create the goal and set the sampling config
goal = GenerateResponse . Goal ()
goal . prompt = self . prompt
goal . sampling_config . temp = 0.2
# add your image to the goal
image = cv2 . imread ( "/path/to/your/image" , cv2 . IMREAD_COLOR )
goal . image = self . cv_bridge . cv2_to_imgmsg ( image )
# wait for the server and send the goal
self . action_client . wait_for_server ()
send_goal_future = self . action_client . send_goal_async (
goal )
# wait for the server
rclpy . spin_until_future_complete ( self , send_goal_future )
get_result_future = send_goal_future . result (). get_result_async ()
# wait again and take the result
rclpy . spin_until_future_complete ( self , get_result_future )
result : GenerateResponse . Result = get_result_future . result (). result
LangChain には llama_ros 統合があります。したがって、迅速なエンジニアリング技術を適用することができます。ここにそれを使用する例があります。
import rclpy
from llama_ros . langchain import LlamaROS
from langchain . prompts import PromptTemplate
from langchain_core . output_parsers import StrOutputParser
rclpy . init ()
# create the llama_ros llm for langchain
llm = LlamaROS ()
# create a prompt template
prompt_template = "tell me a joke about {topic}"
prompt = PromptTemplate (
input_variables = [ "topic" ],
template = prompt_template
)
# create a chain with the llm and the prompt template
chain = prompt | llm | StrOutputParser ()
# run the chain
text = chain . invoke ({ "topic" : "bears" })
print ( text )
rclpy . shutdown ()
import rclpy
from llama_ros . langchain import LlamaROS
from langchain . prompts import PromptTemplate
from langchain_core . output_parsers import StrOutputParser
rclpy . init ()
# create the llama_ros llm for langchain
llm = LlamaROS ()
# create a prompt template
prompt_template = "tell me a joke about {topic}"
prompt = PromptTemplate (
input_variables = [ "topic" ],
template = prompt_template
)
# create a chain with the llm and the prompt template
chain = prompt | llm | StrOutputParser ()
# run the chain
for c in chain . stream ({ "topic" : "bears" }):
print ( c , flush = True , end = "" )
rclpy . shutdown ()
import rclpy
from llama_ros . langchain import LlamaROS
rclpy . init ()
# create the llama_ros llm for langchain
llm = LlamaROS ()
# bind the url_image
llm = llm . bind ( image_url = image_url ). stream ( "Describe the image" )
image_url = "https://upload.wikimedia.org/wikipedia/commons/thumb/d/dd/Gfp-wisconsin-madison-the-nature-boardwalk.jpg/2560px-Gfp-wisconsin-madison-the-nature-boardwalk.jpg"
# run the llm
for c in llm :
print ( c , flush = True , end = "" )
rclpy . shutdown ()
import rclpy
from langchain_chroma import Chroma
from llama_ros . langchain import LlamaROSEmbeddings
rclpy . init ()
# create the llama_ros embeddings for langchain
embeddings = LlamaROSEmbeddings ()
# create a vector database and assign it
db = Chroma ( embedding_function = embeddings )
# create the retriever
retriever = db . as_retriever ( search_kwargs = { "k" : 5 })
# add your texts
db . add_texts ( texts = [ "your_texts" ])
# retrieve documents
documents = retriever . invoke ( "your_query" )
print ( documents )
rclpy . shutdown ()
import rclpy
from llama_ros . langchain import LlamaROSReranker
from llama_ros . langchain import LlamaROSEmbeddings
from langchain_community . vectorstores import FAISS
from langchain_community . document_loaders import TextLoader
from langchain_text_splitters import RecursiveCharacterTextSplitter
from langchain . retrievers import ContextualCompressionRetriever
rclpy . init ()
# load the documents
documents = TextLoader ( "../state_of_the_union.txt" ,). load ()
text_splitter = RecursiveCharacterTextSplitter (
chunk_size = 500 , chunk_overlap = 100 )
texts = text_splitter . split_documents ( documents )
# create the llama_ros embeddings
embeddings = LlamaROSEmbeddings ()
# create the VD and the retriever
retriever = FAISS . from_documents (
texts , embeddings ). as_retriever ( search_kwargs = { "k" : 20 })
# create the compressor using the llama_ros reranker
compressor = LlamaROSReranker ()
compression_retriever = ContextualCompressionRetriever (
base_compressor = compressor , base_retriever = retriever
)
# retrieve the documents
compressed_docs = compression_retriever . invoke (
"What did the president say about Ketanji Jackson Brown"
)
for doc in compressed_docs :
print ( "-" * 50 )
print ( doc . page_content )
print ( " n " )
rclpy . shutdown ()