Skip to content

Bug in multiple action send goal #30

@LeoGori

Description

@LeoGori

I noticed a bug in the generation of the dialogSkill.cpp file when I have multiple send_goal in my high-level state machine. In my case I had these states calling 3 different actions in my high-level DialogSkill.scxml:

Action WaitForInteraction

 <state id="idle">
   ...
    <ros_action_send_goal name="wait_for_interaction_action">
        <field name="is_beginning_of_conversation" expr="m_is_beginning_of_conversation == 'true'"/>
      </ros_action_send_goal>
  </state>

Action BatchGeneration

<state id="sendSynthesizedTextCall">
    ...
      <ros_action_send_goal name="synthesize_text_action">
        <field name="text" expr="m_reply"/>
      </ros_action_send_goal>
...
  </state>

Action Speak

  <state id="speak">
...
      <ros_action_send_goal name="speak_action">
        <field name="text" expr="m_reply"/>
        <field name="dance" expr="m_dance"/>
      </ros_action_send_goal>
...  
</state>

In my generated DialogSkill.cpp, the order of the lambdas containing the action clients is BatchGeneration, WaitForInteraction and Speak. The first one, correctly contains the input parameter as per the high-level definition

m_stateMachine.connectToEvent("TextToSpeechComponent.BatchGeneration.SendGoal", [this]([[maybe_unused]]const QScxmlEvent & event){
    RCLCPP_INFO(m_node->get_logger(), "DialogSkill::TextToSpeechComponent.BatchGeneration.SendGoal");
    RCLCPP_INFO(m_node->get_logger(), "calling send goal");
    std::shared_ptr<rclcpp::Node> nodeBatchGeneration = rclcpp::Node::make_shared(m_name + "SkillNodeBatchGeneration");
    rclcpp_action::Client<text_to_speech_interfaces::action::BatchGeneration>::SharedPtr clientBatchGeneration  =
    rclcpp_action::create_client<text_to_speech_interfaces::action::BatchGeneration>(nodeBatchGeneration, "/TextToSpeechComponent/BatchGeneration");
    text_to_speech_interfaces::action::BatchGeneration::Goal goal_msg;
    
    std::string temp = event.data().toMap()["text"].toString().toStdString();
    goal_msg.text = convert<decltype(goal_msg.text)>(temp);
    
    send_goal(goal_msg);
    RCLCPP_INFO(m_node->get_logger(), "done send goal");
  });

Then the lambda containing the action client for WaitForInteraction contains wrongly, in addition to the input parameter is_beginning_of_conversation defined in the high-level skill, the text parameter, which belongs to the previous lambda:

m_stateMachine.connectToEvent("DialogComponent.WaitForInteraction.SendGoal", [this]([[maybe_unused]]const QScxmlEvent & event){
    RCLCPP_INFO(m_node->get_logger(), "DialogSkill::DialogComponent.WaitForInteraction.SendGoal");
    RCLCPP_INFO(m_node->get_logger(), "calling send goal");
    std::shared_ptr<rclcpp::Node> nodeWaitForInteraction = rclcpp::Node::make_shared(m_name + "SkillNodeWaitForInteraction");
    rclcpp_action::Client<dialog_interfaces::action::WaitForInteraction>::SharedPtr clientWaitForInteraction  =
    rclcpp_action::create_client<dialog_interfaces::action::WaitForInteraction>(nodeWaitForInteraction, "/DialogComponent/WaitForInteraction");
    dialog_interfaces::action::WaitForInteraction::Goal goal_msg;
    
    std::string temp = event.data().toMap()["text"].toString().toStdString();
    goal_msg.text = convert<decltype(goal_msg.text)>(temp);
    
    std::string temp = event.data().toMap()["is_beginning_of_conversation"].toString().toStdString();
    goal_msg.is_beginning_of_conversation = convert<decltype(goal_msg.is_beginning_of_conversation)>(temp);
    
    send_goal(goal_msg);
    RCLCPP_INFO(m_node->get_logger(), "done send goal");
  });

Finally, the lambda containing the action client for Speak is generated with, in addition to the couple of input parameters text and dance defined in the high-level skill, the previous text and is_beginning_of_conversation parameters:

m_stateMachine.connectToEvent("DialogComponent.Speak.SendGoal", [this]([[maybe_unused]]const QScxmlEvent & event){
    RCLCPP_INFO(m_node->get_logger(), "DialogSkill::DialogComponent.Speak.SendGoal");
    RCLCPP_INFO(m_node->get_logger(), "calling send goal");
    std::shared_ptr<rclcpp::Node> nodeSpeak = rclcpp::Node::make_shared(m_name + "SkillNodeSpeak");
    rclcpp_action::Client<dialog_interfaces::action::Speak>::SharedPtr clientSpeak  =
    rclcpp_action::create_client<dialog_interfaces::action::Speak>(nodeSpeak, "/DialogComponent/Speak");
    dialog_interfaces::action::Speak::Goal goal_msg;
    
    std::string temp = event.data().toMap()["text"].toString().toStdString();
    goal_msg.text = convert<decltype(goal_msg.text)>(temp);
    
    std::string temp = event.data().toMap()["is_beginning_of_conversation"].toString().toStdString();
    goal_msg.is_beginning_of_conversation = convert<decltype(goal_msg.is_beginning_of_conversation)>(temp);
    
    std::string temp = event.data().toMap()["text"].toString().toStdString();
    goal_msg.text = convert<decltype(goal_msg.text)>(temp);
    
    std::string temp = event.data().toMap()["dance"].toString().toStdString();
    goal_msg.dance = convert<decltype(goal_msg.dance)>(temp);
    
    send_goal(goal_msg);
    RCLCPP_INFO(m_node->get_logger(), "done send goal");
  });

It seems like the generation appends previously defined action goals' input parameters, missing some logic to reset the list.

Metadata

Metadata

Assignees

No one assigned

    Labels

    No labels
    No labels

    Type

    No type

    Projects

    No projects

    Milestone

    No milestone

    Relationships

    None yet

    Development

    No branches or pull requests

    Issue actions