call.cc
Go to the documentation of this file.
1 /*
2  *
3  * Copyright 2015 gRPC authors.
4  *
5  * Licensed under the Apache License, Version 2.0 (the "License");
6  * you may not use this file except in compliance with the License.
7  * You may obtain a copy of the License at
8  *
9  * http://www.apache.org/licenses/LICENSE-2.0
10  *
11  * Unless required by applicable law or agreed to in writing, software
12  * distributed under the License is distributed on an "AS IS" BASIS,
13  * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
14  * See the License for the specific language governing permissions and
15  * limitations under the License.
16  *
17  */
18 
20 
22 
23 #include <limits.h>
24 #include <stdlib.h>
25 
26 #include <algorithm>
27 #include <atomic>
28 #include <new>
29 #include <string>
30 #include <utility>
31 
32 #include "absl/base/thread_annotations.h"
33 #include "absl/meta/type_traits.h"
34 #include "absl/status/status.h"
35 #include "absl/strings/str_cat.h"
36 #include "absl/strings/str_format.h"
37 #include "absl/strings/string_view.h"
38 
39 #include <grpc/byte_buffer.h>
40 #include <grpc/compression.h>
41 #include <grpc/grpc.h>
44 #include <grpc/slice.h>
45 #include <grpc/slice_buffer.h>
46 #include <grpc/status.h>
47 #include <grpc/support/alloc.h>
48 #include <grpc/support/atm.h>
49 #include <grpc/support/log.h>
51 
57 #include "src/core/lib/gpr/alloc.h"
80 
81 grpc_core::TraceFlag grpc_call_error_trace(false, "call_error");
82 grpc_core::TraceFlag grpc_compression_trace(false, "compression");
83 
84 namespace grpc_core {
85 
86 class Call : public CppImplOf<Call, grpc_call> {
87  public:
88  Arena* arena() { return arena_; }
89  bool is_client() const { return is_client_; }
90 
91  virtual void ContextSet(grpc_context_index elem, void* value,
92  void (*destroy)(void* value)) = 0;
93  virtual void* ContextGet(grpc_context_index elem) const = 0;
94  virtual bool Completed() = 0;
96  virtual void CancelWithError(grpc_error_handle error) = 0;
97  virtual void SetCompletionQueue(grpc_completion_queue* cq) = 0;
98  virtual char* GetPeer() = 0;
99  virtual grpc_call_error StartBatch(const grpc_op* ops, size_t nops,
100  void* notify_tag,
101  bool is_notify_tag_closure) = 0;
102  virtual bool failed_before_recv_message() const = 0;
103  virtual bool is_trailers_only() const = 0;
104  virtual absl::string_view GetServerAuthority() const = 0;
105  virtual void ExternalRef() = 0;
106  virtual void ExternalUnref() = 0;
107  virtual void InternalRef(const char* reason) = 0;
108  virtual void InternalUnref(const char* reason) = 0;
109 
111  virtual uint32_t test_only_message_flags() = 0;
115 
116  // This should return nullptr for the promise stack (and alternative means
117  // for that functionality be invented)
118  virtual grpc_call_stack* call_stack() = 0;
119 
120  protected:
123  GPR_DEBUG_ASSERT(arena_ != nullptr);
124  }
125  ~Call() = default;
126 
127  struct ParentCall {
129  Call* first_child ABSL_GUARDED_BY(child_list_mu) = nullptr;
130  };
131 
132  struct ChildCall {
133  explicit ChildCall(Call* parent) : parent(parent) {}
138  Call* sibling_next = nullptr;
139  Call* sibling_prev = nullptr;
140  };
141 
144 
145  absl::Status InitParent(Call* parent, uint32_t propagation_mask);
146  void PublishToParent(Call* parent);
149 
153  }
154 
155  private:
156  Arena* const arena_;
157  std::atomic<ParentCall*> parent_call_{nullptr};
158  ChildCall* child_ = nullptr;
160  const bool is_client_;
161  // flag indicating that cancellation is inherited
163 };
164 
165 class FilterStackCall final : public Call {
166  public:
168  for (int i = 0; i < GRPC_CONTEXT_COUNT; ++i) {
169  if (context_[i].destroy) {
171  }
172  }
173  gpr_free(static_cast<void*>(const_cast<char*>(final_info_.error_string)));
174  }
175 
176  bool Completed() override {
178  }
179 
180  // TODO(ctiller): return absl::StatusOr<SomeSmartPointer<Call>>?
182  grpc_call** out_call);
183 
186  }
187 
189  return reinterpret_cast<grpc_call_stack*>(
190  reinterpret_cast<char*>(this) +
191  GPR_ROUND_UP_TO_ALIGNMENT_SIZE(sizeof(*this)));
192  }
193 
196  }
197 
199 
200  void CancelWithError(grpc_error_handle error) override;
202  char* GetPeer() override;
203  grpc_call_error StartBatch(const grpc_op* ops, size_t nops, void* notify_tag,
204  bool is_notify_tag_closure) override;
205  void ExternalRef() override { ext_ref_.Ref(); }
206  void ExternalUnref() override;
207  void InternalRef(const char* reason) override {
208  GRPC_CALL_STACK_REF(call_stack(), reason);
209  }
210  void InternalUnref(const char* reason) override {
212  }
213 
215  void (*destroy)(void* value)) override;
216  void* ContextGet(grpc_context_index elem) const override {
217  return context_[elem].value;
218  }
219 
221  grpc_compression_level level) override {
223  }
224 
225  bool is_trailers_only() const override {
226  bool result = is_trailers_only_;
228  return result;
229  }
230 
231  bool failed_before_recv_message() const override {
233  }
234 
236  const Slice* authority_metadata =
238  if (authority_metadata == nullptr) return "";
239  return authority_metadata->as_string_view();
240  }
241 
244  }
245 
248  }
249 
252  }
253 
254  static size_t InitialSizeEstimate() {
255  return sizeof(FilterStackCall) +
257  }
258 
259  private:
260  // The maximum number of concurrent batches possible.
261  // Based upon the maximum number of individually queueable ops in the batch
262  // api:
263  // - initial metadata send
264  // - message send
265  // - status/close send (depending on client/server)
266  // - initial metadata recv
267  // - message recv
268  // - status/close recv (depending on client/server)
269  static constexpr size_t kMaxConcurrentBatches = 6;
270 
271  static constexpr gpr_atm kRecvNone = 0;
272  static constexpr gpr_atm kRecvInitialMetadataFirst = 1;
273 
274  struct BatchControl {
275  FilterStackCall* call_ = nullptr;
277  /* Share memory for cq_completion and notify_tag as they are never needed
278  simultaneously. Each byte used in this data structure count as six bytes
279  per call, so any savings we can make are worthwhile,
280 
281  We use notify_tag to determine whether or not to send notification to the
282  completion queue. Once we've made that determination, we can reuse the
283  memory for cq_completion. */
284  union {
286  struct {
287  /* Any given op indicates completion by either (a) calling a closure or
288  (b) sending a notification on the call's completion queue. If
289  \a is_closure is true, \a tag indicates a closure to be invoked;
290  otherwise, \a tag indicates the tag to be used in the notification to
291  be sent to the completion queue. */
292  void* tag;
294  } notify_tag;
298  std::atomic<intptr_t> steps_to_complete_{0};
301  steps_to_complete_.store(steps, std::memory_order_release);
302  }
304  return steps_to_complete_.fetch_sub(1, std::memory_order_acq_rel) == 1;
305  }
306 
307  void PostCompletion();
308  void FinishStep();
315  };
316 
318  : Call(arena, args.server_transport_data == nullptr, args.send_deadline),
319  cq_(args.cq),
320  channel_(args.channel->Ref()),
322 
323  static void ReleaseCall(void* call, grpc_error_handle);
324  static void DestroyCall(void* call, grpc_error_handle);
325 
327  return reinterpret_cast<FilterStackCall*>(
328  reinterpret_cast<char*>(call_stack) -
330  }
331 
333  grpc_closure* start_batch_closure);
335  BatchControl* ReuseOrAllocateBatchControl(const grpc_op* ops);
337  grpc_compression_algorithm compression_algorithm) GPR_ATTRIBUTE_NOINLINE;
339  grpc_compression_algorithm compression_algorithm) GPR_ATTRIBUTE_NOINLINE;
341  bool is_trailing);
342  void PublishAppMetadata(grpc_metadata_batch* b, bool is_trailing);
345  grpc_error_handle batch_error);
346 
352  gpr_cycle_counter start_time_ = gpr_get_cycle_counter();
353 
355  bool destroy_called_ = false;
356  // Trailers-only response status
357  bool is_trailers_only_ = false;
360  bool sending_message_ = false;
361  bool sent_final_op_ = false;
363  bool receiving_message_ = false;
364  bool requested_final_op_ = false;
366 
369 
370  /* first idx: is_receiving, second idx: is_trailing */
375 
376  /* Buffered read metadata waiting to be returned to the application.
377  Element 0 is initial metadata, element 1 is trailing metadata. */
379 
380  // A char* indicating the peer name.
382 
383  /* Call data useful used for reporting. Only valid after the call has
384  * completed */
386 
387  /* Compression algorithm for *incoming* data */
390  /* Supported encodings (compression algorithms), a bitset.
391  * Always support no compression. */
393 
394  /* Contexts for various subsystems (security, tracing, ...). */
396 
400 
408  // Status about operation of call
411 
413 
414  union {
415  struct {
418  const char** error_string;
419  } client;
420  struct {
421  int* cancelled;
422  // backpointer to owning server if this is a server side call.
424  } server;
425  } final_op_;
427 
428  /* recv_state can contain one of the following values:
429  RECV_NONE : : no initial metadata and messages received
430  RECV_INITIAL_METADATA_FIRST : received initial metadata first
431  a batch_control* : received messages first
432 
433  +------1------RECV_NONE------3-----+
434  | |
435  | |
436  v v
437  RECV_INITIAL_METADATA_FIRST receiving_stream_ready_bctlp
438  | ^ | ^
439  | | | |
440  +-----2-----+ +-----4-----+
441 
442  For 1, 4: See receiving_initial_metadata_ready() function
443  For 2, 3: See receiving_stream_ready() function */
445 };
446 
448  ParentCall* p = parent_call_.load(std::memory_order_acquire);
449  if (p == nullptr) {
450  p = arena_->New<ParentCall>();
451  ParentCall* expected = nullptr;
452  if (!parent_call_.compare_exchange_strong(expected, p,
453  std::memory_order_release,
454  std::memory_order_relaxed)) {
455  p->~ParentCall();
456  p = expected;
457  }
458  }
459  return p;
460 }
461 
463  return parent_call_.load(std::memory_order_acquire);
464 }
465 
466 absl::Status Call::InitParent(Call* parent, uint32_t propagation_mask) {
467  child_ = arena()->New<ChildCall>(parent);
468 
469  parent->InternalRef("child");
471  GPR_ASSERT(!parent->is_client_);
472 
473  if (propagation_mask & GRPC_PROPAGATE_DEADLINE) {
475  }
476  /* for now GRPC_PROPAGATE_TRACING_CONTEXT *MUST* be passed with
477  * GRPC_PROPAGATE_STATS_CONTEXT */
478  /* TODO(ctiller): This should change to use the appropriate census start_op
479  * call. */
480  if (propagation_mask & GRPC_PROPAGATE_CENSUS_TRACING_CONTEXT) {
481  if (0 == (propagation_mask & GRPC_PROPAGATE_CENSUS_STATS_CONTEXT)) {
482  return absl::UnknownError(
483  "Census tracing propagation requested without Census context "
484  "propagation");
485  }
487  nullptr);
488  } else if (propagation_mask & GRPC_PROPAGATE_CENSUS_STATS_CONTEXT) {
489  return absl::UnknownError(
490  "Census context propagation requested without Census tracing "
491  "propagation");
492  }
493  if (propagation_mask & GRPC_PROPAGATE_CANCELLATION) {
495  }
496  return absl::OkStatus();
497 }
498 
500  ChildCall* cc = child_;
501  ParentCall* pc = parent->GetOrCreateParentCall();
502  MutexLock lock(&pc->child_list_mu);
503  if (pc->first_child == nullptr) {
504  pc->first_child = this;
505  cc->sibling_next = cc->sibling_prev = this;
506  } else {
507  cc->sibling_next = pc->first_child;
508  cc->sibling_prev = pc->first_child->child_->sibling_prev;
510  cc->sibling_prev->child_->sibling_next = this;
511  }
512  if (parent->Completed()) {
514  }
515 }
516 
518  grpc_call** out_call) {
519  GPR_TIMER_SCOPE("grpc_call_create", 0);
520 
521  Channel* channel = args->channel.get();
522 
523  auto add_init_error = [](grpc_error_handle* composite,
524  grpc_error_handle new_err) {
525  if (GRPC_ERROR_IS_NONE(new_err)) return;
526  if (GRPC_ERROR_IS_NONE(*composite)) {
527  *composite = GRPC_ERROR_CREATE_FROM_STATIC_STRING("Call creation failed");
528  }
529  *composite = grpc_error_add_child(*composite, new_err);
530  };
531 
532  Arena* arena;
535  grpc_channel_stack* channel_stack = channel->channel_stack();
536  size_t initial_size = channel->CallSizeEstimate();
537  GRPC_STATS_INC_CALL_INITIAL_SIZE(initial_size);
538  size_t call_alloc_size =
540  channel_stack->call_stack_size;
541 
542  std::pair<Arena*, void*> arena_with_call = Arena::CreateWithAlloc(
543  initial_size, call_alloc_size, channel->allocator());
544  arena = arena_with_call.first;
545  call = new (arena_with_call.second) FilterStackCall(arena, *args);
546  GPR_DEBUG_ASSERT(FromC(call->c_ptr()) == call);
547  GPR_DEBUG_ASSERT(FromCallStack(call->call_stack()) == call);
548  *out_call = call->c_ptr();
550  if (call->is_client()) {
551  call->final_op_.client.status_details = nullptr;
552  call->final_op_.client.status = nullptr;
553  call->final_op_.client.error_string = nullptr;
555  path = grpc_slice_ref_internal(args->path->c_slice());
556  call->send_initial_metadata_.Set(HttpPathMetadata(),
557  std::move(*args->path));
558  if (args->authority.has_value()) {
559  call->send_initial_metadata_.Set(HttpAuthorityMetadata(),
560  std::move(*args->authority));
561  }
562  } else {
564  call->final_op_.server.cancelled = nullptr;
565  call->final_op_.server.core_server = args->server;
566  }
567 
568  Call* parent = Call::FromC(args->parent);
569  if (parent != nullptr) {
570  add_init_error(&error, absl_status_to_grpc_error(call->InitParent(
571  parent, args->propagation_mask)));
572  }
573  /* initial refcount dropped by grpc_call_unref */
574  grpc_call_element_args call_args = {
575  call->call_stack(), args->server_transport_data,
576  call->context_, path,
577  call->start_time_, call->send_deadline(),
578  call->arena(), &call->call_combiner_};
579  add_init_error(&error, grpc_call_stack_init(channel_stack, 1, DestroyCall,
580  call, &call_args));
581  // Publish this call to parent only after the call stack has been initialized.
582  if (parent != nullptr) {
583  call->PublishToParent(parent);
584  }
585 
586  if (!GRPC_ERROR_IS_NONE(error)) {
587  call->CancelWithError(GRPC_ERROR_REF(error));
588  }
589  if (args->cq != nullptr) {
590  GPR_ASSERT(args->pollset_set_alternative == nullptr &&
591  "Only one of 'cq' and 'pollset_set_alternative' should be "
592  "non-nullptr.");
593  GRPC_CQ_INTERNAL_REF(args->cq, "bind");
594  call->pollent_ =
596  }
597  if (args->pollset_set_alternative != nullptr) {
599  args->pollset_set_alternative);
600  }
601  if (!grpc_polling_entity_is_empty(&call->pollent_)) {
603  &call->pollent_);
604  }
605 
606  if (call->is_client()) {
607  channelz::ChannelNode* channelz_channel = channel->channelz_node();
608  if (channelz_channel != nullptr) {
609  channelz_channel->RecordCallStarted();
610  }
611  } else if (call->final_op_.server.core_server != nullptr) {
612  channelz::ServerNode* channelz_node =
613  call->final_op_.server.core_server->channelz_node();
614  if (channelz_node != nullptr) {
615  channelz_node->RecordCallStarted();
616  }
617  }
618 
620 
621  return error;
622 }
623 
625  GPR_ASSERT(cq);
626 
627  if (grpc_polling_entity_pollset_set(&pollent_) != nullptr) {
628  gpr_log(GPR_ERROR, "A pollset_set is already registered for this call.");
629  abort();
630  }
631  cq_ = cq;
632  GRPC_CQ_INTERNAL_REF(cq, "bind");
635 }
636 
638  auto* c = static_cast<FilterStackCall*>(call);
640  Arena* arena = c->arena();
641  c->~FilterStackCall();
642  channel->UpdateCallSizeEstimate(arena->Destroy());
643 }
644 
646  GPR_TIMER_SCOPE("destroy_call", 0);
647  auto* c = static_cast<FilterStackCall*>(call);
648  c->recv_initial_metadata_.Clear();
649  c->recv_trailing_metadata_.Clear();
650  c->receiving_slice_buffer_.reset();
651  ParentCall* pc = c->parent_call();
652  if (pc != nullptr) {
653  pc->~ParentCall();
654  }
655  if (c->cq_) {
656  GRPC_CQ_INTERNAL_UNREF(c->cq_, "bind");
657  }
658 
659  grpc_error_handle status_error = c->status_error_.get();
660  grpc_error_get_status(status_error, c->send_deadline(),
661  &c->final_info_.final_status, nullptr, nullptr,
662  &(c->final_info_.error_string));
663  c->status_error_.set(GRPC_ERROR_NONE);
664  c->final_info_.stats.latency =
665  gpr_cycle_counter_sub(gpr_get_cycle_counter(), c->start_time_);
666  grpc_call_stack_destroy(c->call_stack(), &c->final_info_,
667  GRPC_CLOSURE_INIT(&c->release_call_, ReleaseCall, c,
668  grpc_schedule_on_exec_ctx));
669 }
670 
672  ChildCall* cc = child_;
673  if (cc == nullptr) return;
674 
675  ParentCall* pc = cc->parent->parent_call();
676  {
677  MutexLock lock(&pc->child_list_mu);
678  if (this == pc->first_child) {
679  pc->first_child = cc->sibling_next;
680  if (this == pc->first_child) {
681  pc->first_child = nullptr;
682  }
683  }
686  }
687  cc->parent->InternalUnref("child");
688 }
689 
691  if (GPR_LIKELY(!ext_ref_.Unref())) return;
692 
693  GPR_TIMER_SCOPE("grpc_call_unref", 0);
694 
695  ApplicationCallbackExecCtx callback_exec_ctx;
697 
698  GRPC_API_TRACE("grpc_call_unref(c=%p)", 1, (this));
699 
701 
703  destroy_called_ = true;
705  if (cancel) {
707  } else {
708  // Unset the call combiner cancellation closure. This has the
709  // effect of scheduling the previously set cancellation closure, if
710  // any, so that it can release any internal references it may be
711  // holding to the call stack.
713  }
714  InternalUnref("destroy");
715 }
716 
718  char* peer_string = reinterpret_cast<char*>(gpr_atm_acq_load(&peer_string_));
719  if (peer_string != nullptr) return gpr_strdup(peer_string);
720  peer_string = grpc_channel_get_target(channel_->c_ptr());
721  if (peer_string != nullptr) return peer_string;
722  return gpr_strdup("unknown");
723 }
724 
725 // start_batch_closure points to a caller-allocated closure to be used
726 // for entering the call combiner.
728  grpc_closure* start_batch_closure) {
729  // This is called via the call combiner to start sending a batch down
730  // the filter stack.
731  auto execute_batch_in_call_combiner = [](void* arg, grpc_error_handle) {
732  GPR_TIMER_SCOPE("execute_batch_in_call_combiner", 0);
734  static_cast<grpc_transport_stream_op_batch*>(arg);
735  auto* call =
737  grpc_call_element* elem = call->call_elem(0);
739  elem->filter->start_transport_stream_op_batch(elem, batch);
740  };
742  GRPC_CLOSURE_INIT(start_batch_closure, execute_batch_in_call_combiner, batch,
743  grpc_schedule_on_exec_ctx);
744  GRPC_CALL_COMBINER_START(call_combiner(), start_batch_closure,
745  GRPC_ERROR_NONE, "executing batch");
746 }
747 
748 namespace {
749 struct CancelState {
750  FilterStackCall* call;
753 };
754 } // namespace
755 
756 // The on_complete callback used when sending a cancel_stream batch down
757 // the filter stack. Yields the call combiner when the batch is done.
758 static void done_termination(void* arg, grpc_error_handle /*error*/) {
759  CancelState* state = static_cast<CancelState*>(arg);
760  GRPC_CALL_COMBINER_STOP(state->call->call_combiner(),
761  "on_complete for cancel_stream op");
762  state->call->InternalUnref("termination");
763  delete state;
764 }
765 
767  if (!gpr_atm_rel_cas(&cancelled_with_error_, 0, 1)) {
769  return;
770  }
771  InternalRef("termination");
772  // Inform the call combiner of the cancellation, so that it can cancel
773  // any in-flight asynchronous actions that may be holding the call
774  // combiner. This ensures that the cancel_stream batch can be sent
775  // down the filter stack in a timely manner.
777  CancelState* state = new CancelState;
778  state->call = this;
780  grpc_schedule_on_exec_ctx);
782  grpc_make_transport_stream_op(&state->finish_batch);
783  op->cancel_stream = true;
784  op->payload->cancel_stream.cancel_error = error;
785  ExecuteBatch(op, &state->start_batch);
786 }
787 
789  // copying 'description' is needed to ensure the grpc_call_cancel_with_status
790  // guarantee that can be short-lived.
795 }
796 
799  gpr_log(GPR_DEBUG, "set_final_status %s", is_client() ? "CLI" : "SVR");
801  }
802  if (is_client()) {
805  &status_details, nullptr,
806  final_op_.client.error_string);
807  *final_op_.client.status_details =
811  channelz::ChannelNode* channelz_channel = channel_->channelz_node();
812  if (channelz_channel != nullptr) {
813  if (*final_op_.client.status != GRPC_STATUS_OK) {
814  channelz_channel->RecordCallFailed();
815  } else {
816  channelz_channel->RecordCallSucceeded();
817  }
818  }
819  } else {
820  *final_op_.server.cancelled =
822  channelz::ServerNode* channelz_node =
823  final_op_.server.core_server->channelz_node();
824  if (channelz_node != nullptr) {
825  if (*final_op_.server.cancelled || !status_error_.ok()) {
826  channelz_node->RecordCallFailed();
827  } else {
828  channelz_node->RecordCallSucceeded();
829  }
830  }
832  }
833 }
834 
837  bool is_trailing) {
840  for (size_t i = 0; i < count; i++) {
841  grpc_metadata* md = &metadata[i];
842  if (!GRPC_LOG_IF_ERROR("validate_metadata",
844  return false;
845  } else if (!grpc_is_binary_header_internal(md->key) &&
847  "validate_metadata",
849  return false;
850  } else if (GRPC_SLICE_LENGTH(md->value) >= UINT32_MAX) {
851  // HTTP2 hpack encoding has a maximum limit.
852  return false;
853  } else if (grpc_slice_str_cmp(md->key, "content-length") == 0) {
854  // Filter "content-length metadata"
855  continue;
856  }
857  batch->Append(StringViewFromSlice(md->key),
859  [md](absl::string_view error, const Slice& value) {
860  gpr_log(GPR_DEBUG, "Append error: %s",
861  absl::StrCat("key=", StringViewFromSlice(md->key),
862  " error=", error,
863  " value=", value.as_string_view())
864  .c_str());
865  });
866  }
867 
868  return true;
869 }
870 
871 namespace {
872 class PublishToAppEncoder {
873  public:
874  explicit PublishToAppEncoder(grpc_metadata_array* dest) : dest_(dest) {}
875 
876  void Encode(const Slice& key, const Slice& value) {
877  Append(key.c_slice(), value.c_slice());
878  }
879 
880  // Catch anything that is not explicitly handled, and do not publish it to the
881  // application. If new metadata is added to a batch that needs to be
882  // published, it should be called out here.
883  template <typename Which>
884  void Encode(Which, const typename Which::ValueType&) {}
885 
886  void Encode(UserAgentMetadata, const Slice& slice) {
888  }
889 
890  void Encode(HostMetadata, const Slice& slice) {
892  }
893 
894  void Encode(GrpcPreviousRpcAttemptsMetadata, uint32_t count) {
896  }
897 
898  void Encode(GrpcRetryPushbackMsMetadata, Duration count) {
900  }
901 
902  void Encode(LbTokenMetadata, const Slice& slice) {
904  }
905 
906  private:
909  Slice::FromInt64(value).c_slice());
910  }
911 
912  void Append(absl::string_view key, const Slice& value) {
913  Append(StaticSlice::FromStaticString(key).c_slice(), value.c_slice());
914  }
915 
917  auto* mdusr = &dest_->metadata[dest_->count++];
918  mdusr->key = key;
919  mdusr->value = value;
920  }
921 
923 };
924 } // namespace
925 
927  bool is_trailing) {
928  if (b->count() == 0) return;
929  if (!is_client() && is_trailing) return;
930  if (is_trailing && buffered_metadata_[1] == nullptr) return;
931  GPR_TIMER_SCOPE("publish_app_metadata", 0);
933  dest = buffered_metadata_[is_trailing];
934  if (dest->count + b->count() > dest->capacity) {
935  dest->capacity =
936  std::max(dest->capacity + b->count(), dest->capacity * 3 / 2);
937  dest->metadata = static_cast<grpc_metadata*>(
938  gpr_realloc(dest->metadata, sizeof(grpc_metadata) * dest->capacity));
939  }
940  PublishToAppEncoder encoder(dest);
941  b->Encode(&encoder);
942 }
943 
946  b->Take(GrpcEncodingMetadata()).value_or(GRPC_COMPRESS_NONE);
950  PublishAppMetadata(b, false);
951 }
952 
954  grpc_error_handle batch_error) {
955  if (!GRPC_ERROR_IS_NONE(batch_error)) {
956  SetFinalStatus(batch_error);
957  } else {
959  b->Take(GrpcStatusMetadata());
960  if (grpc_status.has_value()) {
961  grpc_status_code status_code = *grpc_status;
963  if (status_code != GRPC_STATUS_OK) {
964  char* peer = GetPeer();
967  absl::StrCat("Error received from peer ", peer)),
968  GRPC_ERROR_INT_GRPC_STATUS, static_cast<intptr_t>(status_code));
969  gpr_free(peer);
970  }
971  auto grpc_message = b->Take(GrpcMessageMetadata());
972  if (grpc_message.has_value()) {
974  grpc_message->as_string_view());
975  } else if (!GRPC_ERROR_IS_NONE(error)) {
977  }
980  } else if (!is_client()) {
982  } else {
984  "Received trailing metadata with no error and no status");
986  GRPC_ERROR_CREATE_FROM_STATIC_STRING("No status received"),
988  }
989  }
990  PublishAppMetadata(b, true);
991 }
992 
993 namespace {
994 bool AreWriteFlagsValid(uint32_t flags) {
995  /* check that only bits in GRPC_WRITE_(INTERNAL?)_USED_MASK are set */
996  const uint32_t allowed_write_positions =
998  const uint32_t invalid_positions = ~allowed_write_positions;
999  return !(flags & invalid_positions);
1000 }
1001 
1002 bool AreInitialMetadataFlagsValid(uint32_t flags) {
1003  /* check that only bits in GRPC_WRITE_(INTERNAL?)_USED_MASK are set */
1004  uint32_t invalid_positions = ~GRPC_INITIAL_METADATA_USED_MASK;
1005  return !(flags & invalid_positions);
1006 }
1007 
1008 size_t BatchSlotForOp(grpc_op_type type) {
1009  switch (type) {
1011  return 0;
1012  case GRPC_OP_SEND_MESSAGE:
1013  return 1;
1016  return 2;
1018  return 3;
1019  case GRPC_OP_RECV_MESSAGE:
1020  return 4;
1023  return 5;
1024  }
1025  GPR_UNREACHABLE_CODE(return 123456789);
1026 }
1027 } // namespace
1028 
1030  const grpc_op* ops) {
1031  size_t slot_idx = BatchSlotForOp(ops[0].op);
1032  BatchControl** pslot = &active_batches_[slot_idx];
1033  BatchControl* bctl;
1034  if (*pslot != nullptr) {
1035  bctl = *pslot;
1036  if (bctl->call_ != nullptr) {
1037  return nullptr;
1038  }
1039  bctl->~BatchControl();
1040  bctl->op_ = {};
1041  new (&bctl->batch_error_) AtomicError();
1042  } else {
1043  bctl = arena()->New<BatchControl>();
1044  *pslot = bctl;
1045  }
1046  bctl->call_ = this;
1047  bctl->op_.payload = &stream_op_payload_;
1048  return bctl;
1049 }
1050 
1052  ParentCall* pc = parent_call();
1053  if (pc != nullptr) {
1054  Call* child;
1055  MutexLock lock(&pc->child_list_mu);
1056  child = pc->first_child;
1057  if (child != nullptr) {
1058  do {
1059  Call* next_child_call = child->child_->sibling_next;
1060  if (child->cancellation_is_inherited_) {
1061  child->InternalRef("propagate_cancel");
1062  child->CancelWithError(GRPC_ERROR_CANCELLED);
1063  child->InternalUnref("propagate_cancel");
1064  }
1065  child = next_child_call;
1066  } while (child != pc->first_child);
1067  }
1068  }
1069 }
1070 
1074 
1075  if (op_.send_initial_metadata) {
1076  call->send_initial_metadata_.Clear();
1077  }
1078  if (op_.send_message) {
1079  if (op_.payload->send_message.stream_write_closed &&
1083  "Attempt to send message after stream was closed."));
1084  }
1085  call->sending_message_ = false;
1086  call->send_slice_buffer_.Clear();
1087  }
1089  call->send_trailing_metadata_.Clear();
1090  }
1092  /* propagate cancellation to any interested children */
1093  gpr_atm_rel_store(&call->received_final_op_atm_, 1);
1094  call->PropagateCancellationToChildren();
1097  }
1099  *call->receiving_buffer_ != nullptr) {
1100  grpc_byte_buffer_destroy(*call->receiving_buffer_);
1101  *call->receiving_buffer_ = nullptr;
1102  }
1104 
1105  if (completion_data_.notify_tag.is_closure) {
1106  /* unrefs error */
1107  call_ = nullptr;
1109  static_cast<grpc_closure*>(completion_data_.notify_tag.tag),
1110  error);
1111  call->InternalUnref("completion");
1112  } else {
1113  /* unrefs error */
1115  call->cq_, completion_data_.notify_tag.tag, error,
1116  [](void* user_data, grpc_cq_completion* /*storage*/) {
1117  BatchControl* bctl = static_cast<BatchControl*>(user_data);
1118  Call* call = bctl->call_;
1119  bctl->call_ = nullptr;
1120  call->InternalUnref("completion");
1121  },
1122  this, &completion_data_.cq_completion);
1123  }
1124 }
1125 
1127  if (GPR_UNLIKELY(completed_batch_step())) {
1128  PostCompletion();
1129  }
1130 }
1131 
1134  if (!call->receiving_slice_buffer_.has_value()) {
1135  *call->receiving_buffer_ = nullptr;
1136  call->receiving_message_ = false;
1137  FinishStep();
1138  } else {
1139  call->test_only_last_message_flags_ = call->receiving_stream_flags_;
1140  if ((call->receiving_stream_flags_ & GRPC_WRITE_INTERNAL_COMPRESS) &&
1141  (call->incoming_compression_algorithm_ != GRPC_COMPRESS_NONE)) {
1142  *call->receiving_buffer_ = grpc_raw_compressed_byte_buffer_create(
1143  nullptr, 0, call->incoming_compression_algorithm_);
1144  } else {
1145  *call->receiving_buffer_ = grpc_raw_byte_buffer_create(nullptr, 0);
1146  }
1148  call->receiving_slice_buffer_->c_slice_buffer(),
1149  &(*call->receiving_buffer_)->data.raw.slice_buffer);
1150  call->receiving_message_ = false;
1151  call->receiving_slice_buffer_.reset();
1152  FinishStep();
1153  }
1154 }
1155 
1159  if (!GRPC_ERROR_IS_NONE(error)) {
1160  call->receiving_slice_buffer_.reset();
1161  if (batch_error_.ok()) {
1162  batch_error_.set(error);
1163  }
1164  call->CancelWithError(GRPC_ERROR_REF(error));
1165  }
1166  /* If recv_state is kRecvNone, we will save the batch_control
1167  * object with rel_cas, and will not use it after the cas. Its corresponding
1168  * acq_load is in receiving_initial_metadata_ready() */
1169  if (!GRPC_ERROR_IS_NONE(error) ||
1170  !call->receiving_slice_buffer_.has_value() ||
1171  !gpr_atm_rel_cas(&call->recv_state_, kRecvNone,
1172  reinterpret_cast<gpr_atm>(this))) {
1173  ProcessDataAfterMetadata();
1174  }
1175 }
1176 
1178  grpc_compression_algorithm compression_algorithm) {
1179  const char* algo_name = nullptr;
1180  grpc_compression_algorithm_name(compression_algorithm, &algo_name);
1181  std::string error_msg =
1182  absl::StrFormat("Compression algorithm '%s' is disabled.", algo_name);
1183  gpr_log(GPR_ERROR, "%s", error_msg.c_str());
1184  CancelWithStatus(GRPC_STATUS_UNIMPLEMENTED, error_msg.c_str());
1185 }
1186 
1188  grpc_compression_algorithm compression_algorithm) {
1189  const char* algo_name = nullptr;
1190  grpc_compression_algorithm_name(compression_algorithm, &algo_name);
1192  "Compression algorithm ('%s') not present in the "
1193  "accepted encodings (%s)",
1194  algo_name,
1196 }
1197 
1200 
1201  const grpc_compression_options compression_options =
1202  call->channel_->compression_options();
1203  const grpc_compression_algorithm compression_algorithm =
1204  call->incoming_compression_algorithm_;
1206  compression_options.enabled_algorithms_bitset)
1207  .IsSet(compression_algorithm))) {
1208  /* check if algorithm is supported by current channel config */
1209  call->HandleCompressionAlgorithmDisabled(compression_algorithm);
1210  }
1211  /* GRPC_COMPRESS_NONE is always set. */
1212  GPR_DEBUG_ASSERT(call->encodings_accepted_by_peer_.IsSet(GRPC_COMPRESS_NONE));
1213  if (GPR_UNLIKELY(
1214  !call->encodings_accepted_by_peer_.IsSet(compression_algorithm))) {
1216  call->HandleCompressionAlgorithmNotAccepted(compression_algorithm);
1217  }
1218  }
1219 }
1220 
1224 
1225  GRPC_CALL_COMBINER_STOP(call->call_combiner(), "recv_initial_metadata_ready");
1226 
1227  if (GRPC_ERROR_IS_NONE(error)) {
1228  grpc_metadata_batch* md = &call->recv_initial_metadata_;
1229  call->RecvInitialFilter(md);
1230 
1231  /* TODO(ctiller): this could be moved into recv_initial_filter now */
1232  GPR_TIMER_SCOPE("validate_filtered_metadata", 0);
1233  ValidateFilteredMetadata();
1234 
1236  if (deadline.has_value() && !call->is_client()) {
1237  call_->set_send_deadline(*deadline);
1238  }
1239  } else {
1240  if (batch_error_.ok()) {
1241  batch_error_.set(error);
1242  }
1243  call->CancelWithError(GRPC_ERROR_REF(error));
1244  }
1245 
1246  grpc_closure* saved_rsr_closure = nullptr;
1247  while (true) {
1248  gpr_atm rsr_bctlp = gpr_atm_acq_load(&call->recv_state_);
1249  /* Should only receive initial metadata once */
1250  GPR_ASSERT(rsr_bctlp != 1);
1251  if (rsr_bctlp == 0) {
1252  /* We haven't seen initial metadata and messages before, thus initial
1253  * metadata is received first.
1254  * no_barrier_cas is used, as this function won't access the batch_control
1255  * object saved by receiving_stream_ready() if the initial metadata is
1256  * received first. */
1257  if (gpr_atm_no_barrier_cas(&call->recv_state_, kRecvNone,
1259  break;
1260  }
1261  } else {
1262  /* Already received messages */
1263  saved_rsr_closure = GRPC_CLOSURE_CREATE(
1264  [](void* bctl, grpc_error_handle error) {
1265  static_cast<BatchControl*>(bctl)->ReceivingStreamReady(error);
1266  },
1267  reinterpret_cast<BatchControl*>(rsr_bctlp),
1268  grpc_schedule_on_exec_ctx);
1269  /* No need to modify recv_state */
1270  break;
1271  }
1272  }
1273  if (saved_rsr_closure != nullptr) {
1274  Closure::Run(DEBUG_LOCATION, saved_rsr_closure, GRPC_ERROR_REF(error));
1275  }
1276 
1277  FinishStep();
1278 }
1279 
1282  GRPC_CALL_COMBINER_STOP(call_->call_combiner(),
1283  "recv_trailing_metadata_ready");
1284  grpc_metadata_batch* md = &call_->recv_trailing_metadata_;
1285  call_->RecvTrailingFilter(md, GRPC_ERROR_REF(error));
1286  FinishStep();
1287 }
1288 
1290  GRPC_CALL_COMBINER_STOP(call_->call_combiner(), "on_complete");
1291  if (batch_error_.ok()) {
1292  batch_error_.set(error);
1293  }
1294  if (!GRPC_ERROR_IS_NONE(error)) {
1295  call_->CancelWithError(GRPC_ERROR_REF(error));
1296  }
1297  FinishStep();
1298 }
1299 
1301  void* notify_tag,
1302  bool is_notify_tag_closure) {
1303  GPR_TIMER_SCOPE("call_start_batch", 0);
1304 
1305  size_t i;
1306  const grpc_op* op;
1307  BatchControl* bctl;
1308  bool has_send_ops = false;
1309  int num_recv_ops = 0;
1311  grpc_transport_stream_op_batch* stream_op;
1312  grpc_transport_stream_op_batch_payload* stream_op_payload;
1313  uint32_t seen_ops = 0;
1314 
1315  for (i = 0; i < nops; i++) {
1316  if (seen_ops & (1u << ops[i].op)) {
1318  }
1319  seen_ops |= (1u << ops[i].op);
1320  }
1321 
1323 
1324  if (nops == 0) {
1325  if (!is_notify_tag_closure) {
1326  GPR_ASSERT(grpc_cq_begin_op(cq_, notify_tag));
1328  cq_, notify_tag, GRPC_ERROR_NONE,
1330  nullptr,
1331  static_cast<grpc_cq_completion*>(
1332  gpr_malloc(sizeof(grpc_cq_completion))));
1333  } else {
1334  Closure::Run(DEBUG_LOCATION, static_cast<grpc_closure*>(notify_tag),
1335  GRPC_ERROR_NONE);
1336  }
1337  error = GRPC_CALL_OK;
1338  goto done;
1339  }
1340 
1342  if (bctl == nullptr) {
1344  }
1345  bctl->completion_data_.notify_tag.tag = notify_tag;
1346  bctl->completion_data_.notify_tag.is_closure =
1347  static_cast<uint8_t>(is_notify_tag_closure != 0);
1348 
1349  stream_op = &bctl->op_;
1350  stream_op_payload = &stream_op_payload_;
1351 
1352  /* rewrite batch ops into a transport op */
1353  for (i = 0; i < nops; i++) {
1354  op = &ops[i];
1355  if (op->reserved != nullptr) {
1357  goto done_with_error;
1358  }
1359  switch (op->op) {
1361  /* Flag validation: currently allow no flags */
1362  if (!AreInitialMetadataFlagsValid(op->flags)) {
1364  goto done_with_error;
1365  }
1366  if (sent_initial_metadata_) {
1368  goto done_with_error;
1369  }
1370  // TODO(juanlishen): If the user has already specified a compression
1371  // algorithm by setting the initial metadata with key of
1372  // GRPC_COMPRESSION_REQUEST_ALGORITHM_MD_KEY, we shouldn't override that
1373  // with the compression algorithm mapped from compression level.
1374  /* process compression level */
1375  grpc_compression_level effective_compression_level =
1377  bool level_set = false;
1379  effective_compression_level =
1381  level_set = true;
1382  } else {
1384  channel_->compression_options();
1385  if (copts.default_level.is_set) {
1386  level_set = true;
1387  effective_compression_level = copts.default_level.level;
1388  }
1389  }
1390  // Currently, only server side supports compression level setting.
1391  if (level_set && !is_client()) {
1392  const grpc_compression_algorithm calgo =
1394  effective_compression_level);
1395  // The following metadata will be checked and removed by the message
1396  // compression filter. It will be used as the call's compression
1397  // algorithm.
1399  }
1400  if (op->data.send_initial_metadata.count > INT_MAX) {
1402  goto done_with_error;
1403  }
1404  stream_op->send_initial_metadata = true;
1405  sent_initial_metadata_ = true;
1408  false)) {
1410  goto done_with_error;
1411  }
1412  // Ignore any te metadata key value pairs specified.
1414  /* TODO(ctiller): just make these the same variable? */
1415  if (is_client() && send_deadline() != Timestamp::InfFuture()) {
1417  }
1418  stream_op_payload->send_initial_metadata.send_initial_metadata =
1420  stream_op_payload->send_initial_metadata.send_initial_metadata_flags =
1421  op->flags;
1422  if (is_client()) {
1423  stream_op_payload->send_initial_metadata.peer_string = &peer_string_;
1424  }
1425  has_send_ops = true;
1426  break;
1427  }
1428  case GRPC_OP_SEND_MESSAGE: {
1429  if (!AreWriteFlagsValid(op->flags)) {
1431  goto done_with_error;
1432  }
1433  if (op->data.send_message.send_message == nullptr) {
1435  goto done_with_error;
1436  }
1437  if (sending_message_) {
1439  goto done_with_error;
1440  }
1441  uint32_t flags = op->flags;
1442  /* If the outgoing buffer is already compressed, mark it as so in the
1443  flags. These will be picked up by the compression filter and further
1444  (wasteful) attempts at compression skipped. */
1448  }
1449  stream_op->send_message = true;
1450  sending_message_ = true;
1455  stream_op_payload->send_message.flags = flags;
1456  stream_op_payload->send_message.send_message = &send_slice_buffer_;
1457  has_send_ops = true;
1458  break;
1459  }
1461  /* Flag validation: currently allow no flags */
1462  if (op->flags != 0) {
1464  goto done_with_error;
1465  }
1466  if (!is_client()) {
1468  goto done_with_error;
1469  }
1470  if (sent_final_op_) {
1472  goto done_with_error;
1473  }
1474  stream_op->send_trailing_metadata = true;
1475  sent_final_op_ = true;
1476  stream_op_payload->send_trailing_metadata.send_trailing_metadata =
1478  has_send_ops = true;
1479  break;
1480  }
1482  /* Flag validation: currently allow no flags */
1483  if (op->flags != 0) {
1485  goto done_with_error;
1486  }
1487  if (is_client()) {
1489  goto done_with_error;
1490  }
1491  if (sent_final_op_) {
1493  goto done_with_error;
1494  }
1496  INT_MAX) {
1498  goto done_with_error;
1499  }
1500  stream_op->send_trailing_metadata = true;
1501  sent_final_op_ = true;
1502 
1507  goto done_with_error;
1508  }
1509 
1510  grpc_error_handle status_error =
1512  ? GRPC_ERROR_NONE
1515  "Server returned error"),
1517  static_cast<intptr_t>(
1519  if (op->data.send_status_from_server.status_details != nullptr) {
1524  if (!GRPC_ERROR_IS_NONE(status_error)) {
1525  status_error = grpc_error_set_str(
1526  status_error, GRPC_ERROR_STR_GRPC_MESSAGE,
1529  }
1530  }
1531 
1532  status_error_.set(status_error);
1533  GRPC_ERROR_UNREF(status_error);
1534 
1537 
1538  // Ignore any te metadata key value pairs specified.
1540  stream_op_payload->send_trailing_metadata.send_trailing_metadata =
1542  stream_op_payload->send_trailing_metadata.sent =
1544  has_send_ops = true;
1545  break;
1546  }
1548  /* Flag validation: currently allow no flags */
1549  if (op->flags != 0) {
1551  goto done_with_error;
1552  }
1555  goto done_with_error;
1556  }
1558  buffered_metadata_[0] =
1562  [](void* bctl, grpc_error_handle error) {
1563  static_cast<BatchControl*>(bctl)->ReceivingInitialMetadataReady(
1564  error);
1565  },
1566  bctl, grpc_schedule_on_exec_ctx);
1567  stream_op->recv_initial_metadata = true;
1568  stream_op_payload->recv_initial_metadata.recv_initial_metadata =
1570  stream_op_payload->recv_initial_metadata.recv_initial_metadata_ready =
1572  if (is_client()) {
1573  stream_op_payload->recv_initial_metadata.trailing_metadata_available =
1575  } else {
1576  stream_op_payload->recv_initial_metadata.peer_string = &peer_string_;
1577  }
1578  ++num_recv_ops;
1579  break;
1580  }
1581  case GRPC_OP_RECV_MESSAGE: {
1582  /* Flag validation: currently allow no flags */
1583  if (op->flags != 0) {
1585  goto done_with_error;
1586  }
1587  if (receiving_message_) {
1589  goto done_with_error;
1590  }
1591  receiving_message_ = true;
1592  stream_op->recv_message = true;
1593  receiving_slice_buffer_.reset();
1595  stream_op_payload->recv_message.recv_message = &receiving_slice_buffer_;
1597  stream_op_payload->recv_message.flags = &receiving_stream_flags_;
1598  stream_op_payload->recv_message.call_failed_before_recv_message =
1602  [](void* bctlp, grpc_error_handle error) {
1603  auto* bctl = static_cast<BatchControl*>(bctlp);
1604  auto* call = bctl->call_;
1605  // Yields the call combiner before processing the received
1606  // message.
1607  GRPC_CALL_COMBINER_STOP(call->call_combiner(),
1608  "recv_message_ready");
1609  bctl->ReceivingStreamReady(error);
1610  },
1611  bctl, grpc_schedule_on_exec_ctx);
1612  stream_op_payload->recv_message.recv_message_ready =
1614  ++num_recv_ops;
1615  break;
1616  }
1618  /* Flag validation: currently allow no flags */
1619  if (op->flags != 0) {
1621  goto done_with_error;
1622  }
1623  if (!is_client()) {
1625  goto done_with_error;
1626  }
1627  if (requested_final_op_) {
1629  goto done_with_error;
1630  }
1631  requested_final_op_ = true;
1632  buffered_metadata_[1] =
1634  final_op_.client.status = op->data.recv_status_on_client.status;
1635  final_op_.client.status_details =
1637  final_op_.client.error_string =
1639  stream_op->recv_trailing_metadata = true;
1640  stream_op_payload->recv_trailing_metadata.recv_trailing_metadata =
1642  stream_op_payload->recv_trailing_metadata.collect_stats =
1646  [](void* bctl, grpc_error_handle error) {
1647  static_cast<BatchControl*>(bctl)->ReceivingTrailingMetadataReady(
1648  error);
1649  },
1650  bctl, grpc_schedule_on_exec_ctx);
1651  stream_op_payload->recv_trailing_metadata.recv_trailing_metadata_ready =
1653  ++num_recv_ops;
1654  break;
1655  }
1657  /* Flag validation: currently allow no flags */
1658  if (op->flags != 0) {
1660  goto done_with_error;
1661  }
1662  if (is_client()) {
1664  goto done_with_error;
1665  }
1666  if (requested_final_op_) {
1668  goto done_with_error;
1669  }
1670  requested_final_op_ = true;
1671  final_op_.server.cancelled = op->data.recv_close_on_server.cancelled;
1672  stream_op->recv_trailing_metadata = true;
1673  stream_op_payload->recv_trailing_metadata.recv_trailing_metadata =
1675  stream_op_payload->recv_trailing_metadata.collect_stats =
1679  [](void* bctl, grpc_error_handle error) {
1680  static_cast<BatchControl*>(bctl)->ReceivingTrailingMetadataReady(
1681  error);
1682  },
1683  bctl, grpc_schedule_on_exec_ctx);
1684  stream_op_payload->recv_trailing_metadata.recv_trailing_metadata_ready =
1686  ++num_recv_ops;
1687  break;
1688  }
1689  }
1690  }
1691 
1692  InternalRef("completion");
1693  if (!is_notify_tag_closure) {
1694  GPR_ASSERT(grpc_cq_begin_op(cq_, notify_tag));
1695  }
1696  bctl->set_num_steps_to_complete((has_send_ops ? 1 : 0) + num_recv_ops);
1697 
1698  if (has_send_ops) {
1700  &bctl->finish_batch_,
1701  [](void* bctl, grpc_error_handle error) {
1702  static_cast<BatchControl*>(bctl)->FinishBatch(error);
1703  },
1704  bctl, grpc_schedule_on_exec_ctx);
1705  stream_op->on_complete = &bctl->finish_batch_;
1706  }
1707 
1708  ExecuteBatch(stream_op, &bctl->start_batch_);
1709 
1710 done:
1711  return error;
1712 
1713 done_with_error:
1714  /* reverse any mutations that occurred */
1715  if (stream_op->send_initial_metadata) {
1716  sent_initial_metadata_ = false;
1718  }
1719  if (stream_op->send_message) {
1720  sending_message_ = false;
1721  }
1722  if (stream_op->send_trailing_metadata) {
1723  sent_final_op_ = false;
1725  }
1726  if (stream_op->recv_initial_metadata) {
1728  }
1729  if (stream_op->recv_message) {
1730  receiving_message_ = false;
1731  }
1732  if (stream_op->recv_trailing_metadata) {
1733  requested_final_op_ = false;
1734  }
1735  goto done;
1736 }
1737 
1739  void (*destroy)(void*)) {
1740  if (context_[elem].destroy) {
1742  }
1743  context_[elem].value = value;
1745 }
1746 
1747 } // namespace grpc_core
1748 
1752 }
1753 
1756 }
1757 
1759  grpc_call** out_call) {
1760  return grpc_core::FilterStackCall::Create(args, out_call);
1761 }
1762 
1766 }
1767 
1769 
1772 }
1773 
1775  return grpc_core::Call::FromC(call)->GetPeer();
1776 }
1777 
1779  return grpc_core::FilterStackCall::FromTopElem(surface_element)->c_ptr();
1780 }
1781 
1783  GRPC_API_TRACE("grpc_call_cancel(call=%p, reserved=%p)", 2, (call, reserved));
1784  GPR_ASSERT(reserved == nullptr);
1785  grpc_core::ApplicationCallbackExecCtx callback_exec_ctx;
1788  return GRPC_CALL_OK;
1789 }
1790 
1793  const char* description,
1794  void* reserved) {
1796  "grpc_call_cancel_with_status("
1797  "c=%p, status=%d, description=%s, reserved=%p)",
1798  4, (c, (int)status, description, reserved));
1799  GPR_ASSERT(reserved == nullptr);
1800  grpc_core::ApplicationCallbackExecCtx callback_exec_ctx;
1803  return GRPC_CALL_OK;
1804 }
1805 
1808 }
1809 
1811  grpc_call* call) {
1813 }
1814 
1817 }
1818 
1821 }
1822 
1824  return grpc_core::Call::FromC(call)->arena();
1825 }
1826 
1829 }
1830 
1832  size_t nops, void* tag, void* reserved) {
1834  "grpc_call_start_batch(call=%p, ops=%p, nops=%lu, tag=%p, "
1835  "reserved=%p)",
1836  5, (call, ops, (unsigned long)nops, tag, reserved));
1837 
1838  if (reserved != nullptr) {
1839  return GRPC_CALL_ERROR;
1840  } else {
1841  grpc_core::ApplicationCallbackExecCtx callback_exec_ctx;
1843  return grpc_core::Call::FromC(call)->StartBatch(ops, nops, tag, false);
1844  }
1845 }
1846 
1848  const grpc_op* ops,
1849  size_t nops,
1850  grpc_closure* closure) {
1851  return grpc_core::Call::FromC(call)->StartBatch(ops, nops, closure, true);
1852 }
1853 
1855  void* value, void (*destroy)(void* value)) {
1857 }
1858 
1861 }
1862 
1865 }
1866 
1870 }
1871 
1874 }
1875 
1878 }
1879 
1882 }
1883 
1885  switch (error) {
1886  case GRPC_CALL_ERROR:
1887  return "GRPC_CALL_ERROR";
1889  return "GRPC_CALL_ERROR_ALREADY_ACCEPTED";
1891  return "GRPC_CALL_ERROR_ALREADY_FINISHED";
1893  return "GRPC_CALL_ERROR_ALREADY_INVOKED";
1895  return "GRPC_CALL_ERROR_BATCH_TOO_BIG";
1897  return "GRPC_CALL_ERROR_INVALID_FLAGS";
1899  return "GRPC_CALL_ERROR_INVALID_MESSAGE";
1901  return "GRPC_CALL_ERROR_INVALID_METADATA";
1903  return "GRPC_CALL_ERROR_NOT_INVOKED";
1905  return "GRPC_CALL_ERROR_NOT_ON_CLIENT";
1907  return "GRPC_CALL_ERROR_NOT_ON_SERVER";
1909  return "GRPC_CALL_ERROR_NOT_SERVER_COMPLETION_QUEUE";
1911  return "GRPC_CALL_ERROR_PAYLOAD_TYPE_MISMATCH";
1913  return "GRPC_CALL_ERROR_TOO_MANY_OPERATIONS";
1915  return "GRPC_CALL_ERROR_COMPLETION_QUEUE_SHUTDOWN";
1916  case GRPC_CALL_OK:
1917  return "GRPC_CALL_OK";
1918  }
1919  GPR_UNREACHABLE_CODE(return "GRPC_CALL_ERROR_UNKNOW");
1920 }
grpc_core::FilterStackCall::receiving_slice_buffer_
absl::optional< SliceBuffer > receiving_slice_buffer_
Definition: call.cc:398
GRPC_CLOSURE_INIT
#define GRPC_CLOSURE_INIT(closure, cb, cb_arg, scheduler)
Definition: closure.h:115
grpc_core::Channel
Definition: src/core/lib/surface/channel.h:108
grpc_compression_trace
grpc_core::TraceFlag grpc_compression_trace(false, "compression")
grpc_core::RefCount::Ref
void Ref(Value n=1)
Definition: ref_counted.h:68
grpc_validate_header_nonbin_value_is_legal
grpc_error_handle grpc_validate_header_nonbin_value_is_legal(const grpc_slice &slice)
Definition: validate_metadata.cc:116
grpc_core::Call::InternalUnref
virtual void InternalUnref(const char *reason)=0
_gevent_test_main.result
result
Definition: _gevent_test_main.py:96
compression.h
GPR_INFO
#define GPR_INFO
Definition: include/grpc/impl/codegen/log.h:56
grpc_op::grpc_op_data::grpc_op_send_message::send_message
struct grpc_byte_buffer * send_message
Definition: grpc_types.h:668
grpc_core::FilterStackCall::GetServerAuthority
absl::string_view GetServerAuthority() const override
Definition: call.cc:235
grpc_op::flags
uint32_t flags
Definition: grpc_types.h:644
grpc_core::FilterStackCall::ReleaseCall
static void ReleaseCall(void *call, grpc_error_handle)
Definition: call.cc:637
grpc_call_error
grpc_call_error
Definition: grpc_types.h:464
grpc_slice_buffer_move_into
GPRAPI void grpc_slice_buffer_move_into(grpc_slice_buffer *src, grpc_slice_buffer *dst)
Definition: slice/slice_buffer.cc:291
grpc_compression_options::enabled_algorithms_bitset
uint32_t enabled_algorithms_bitset
Definition: compression_types.h:84
grpc_core::CallCombiner
Definition: call_combiner.h:50
grpc_core::GrpcTimeoutMetadata
Definition: metadata_batch.h:59
GRPC_CALL_ERROR_ALREADY_INVOKED
@ GRPC_CALL_ERROR_ALREADY_INVOKED
Definition: grpc_types.h:476
grpc_core::MetadataMap::Set
absl::enable_if_t< Which::kRepeatable==false, void > Set(Which, Args &&... args)
Definition: metadata_batch.h:1075
grpc_metadata_array::metadata
grpc_metadata * metadata
Definition: grpc_types.h:582
grpc_core::FilterStackCall::error_string
const char ** error_string
Definition: call.cc:418
grpc_op::grpc_op_data::grpc_op_recv_status_on_client::trailing_metadata
grpc_metadata_array * trailing_metadata
Definition: grpc_types.h:701
GRPC_ERROR_NONE
#define GRPC_ERROR_NONE
Definition: error.h:234
GRPC_CALL_LOG_BATCH
#define GRPC_CALL_LOG_BATCH(sev, ops, nops)
Definition: src/core/lib/surface/call.h:105
log.h
grpc_core::Call::GetServerAuthority
virtual absl::string_view GetServerAuthority() const =0
grpc_core::Call::cancellation_is_inherited_
bool cancellation_is_inherited_
Definition: call.cc:162
grpc_call_arena_alloc
void * grpc_call_arena_alloc(grpc_call *call, size_t size)
Definition: call.cc:1749
GRPC_ERROR_CREATE_FROM_COPIED_STRING
#define GRPC_ERROR_CREATE_FROM_COPIED_STRING(desc)
Definition: error.h:294
grpc_core::FilterStackCall::core_server
Server * core_server
Definition: call.cc:423
grpc_core::Call
Definition: call.cc:86
grpc_op::grpc_op_data::grpc_op_recv_status_on_client::status
grpc_status_code * status
Definition: grpc_types.h:702
metadata_batch.h
grpc_core::Call::is_client_
const bool is_client_
Definition: call.cc:160
grpc_core::FilterStackCall::status
grpc_status_code * status
Definition: call.cc:416
grpc_raw_byte_buffer_create
GRPCAPI grpc_byte_buffer * grpc_raw_byte_buffer_create(grpc_slice *slices, size_t nslices)
Definition: byte_buffer.cc:34
grpc_slice_ref_internal
const grpc_slice & grpc_slice_ref_internal(const grpc_slice &slice)
Definition: slice_refcount.h:32
GRPC_CALL_ERROR_TOO_MANY_OPERATIONS
@ GRPC_CALL_ERROR_TOO_MANY_OPERATIONS
Definition: grpc_types.h:483
grpc_core::CallCombiner::SetNotifyOnCancel
void SetNotifyOnCancel(grpc_closure *closure)
Definition: call_combiner.cc:212
grpc_core::FilterStackCall::ext_ref_
RefCount ext_ref_
Definition: call.cc:347
absl::StrCat
std::string StrCat(const AlphaNum &a, const AlphaNum &b)
Definition: abseil-cpp/absl/strings/str_cat.cc:98
metadata
Definition: cq_verifier.cc:48
grpc_raw_compressed_byte_buffer_create
GRPCAPI grpc_byte_buffer * grpc_raw_compressed_byte_buffer_create(grpc_slice *slices, size_t nslices, grpc_compression_algorithm compression)
Definition: byte_buffer.cc:40
call_
grpc_call * call_
Definition: rls.cc:669
grpc_call_create
grpc_error_handle grpc_call_create(grpc_call_create_args *args, grpc_call **out_call)
Definition: call.cc:1758
grpc_channel_stack
Definition: channel_stack.h:202
absl::StrFormat
ABSL_MUST_USE_RESULT std::string StrFormat(const FormatSpec< Args... > &format, const Args &... args)
Definition: abseil-cpp/absl/strings/str_format.h:338
GPR_DEBUG_ASSERT
#define GPR_DEBUG_ASSERT(x)
Definition: include/grpc/impl/codegen/log.h:103
copts
Definition: abseil-cpp/absl/copts/copts.py:1
timers.h
GRPC_CALL_ERROR
@ GRPC_CALL_ERROR
Definition: grpc_types.h:468
polling_entity.h
GRPC_CALL_ERROR_INVALID_MESSAGE
@ GRPC_CALL_ERROR_INVALID_MESSAGE
Definition: grpc_types.h:489
grpc_op::grpc_op_data::grpc_op_send_initial_metadata::grpc_op_send_initial_metadata_maybe_compression_level::level
grpc_compression_level level
Definition: grpc_types.h:659
grpc_core::FilterStackCall::PrepareApplicationMetadata
bool PrepareApplicationMetadata(size_t count, grpc_metadata *metadata, bool is_trailing)
Definition: call.cc:835
grpc_transport_stream_op_batch::recv_message
bool recv_message
Definition: transport.h:322
grpc_core::FilterStackCall::receiving_message_
bool receiving_message_
Definition: call.cc:363
grpc_op::grpc_op_data::send_initial_metadata
struct grpc_op::grpc_op_data::grpc_op_send_initial_metadata send_initial_metadata
grpc_core::CompressionAlgorithmSet
Definition: compression_internal.h:52
grpc_call_set_completion_queue
void grpc_call_set_completion_queue(grpc_call *call, grpc_completion_queue *cq)
Definition: call.cc:1763
slice.h
grpc_core::FilterStackCall::BatchControl::steps_to_complete_
std::atomic< intptr_t > steps_to_complete_
Definition: call.cc:298
AtomicError
Definition: error.h:403
grpc_core::FilterStackCall::BatchControl::batch_error_
AtomicError batch_error_
Definition: call.cc:299
grpc_core::Call::Call
Call(Arena *arena, bool is_client, Timestamp send_deadline)
Definition: call.cc:121
grpc.framework.interfaces.base.utilities.completion
def completion(terminal_metadata, code, message)
Definition: framework/interfaces/base/utilities.py:45
grpc_core::FilterStackCall::received_initial_metadata_
bool received_initial_metadata_
Definition: call.cc:362
GPR_TIMER_SCOPE
#define GPR_TIMER_SCOPE(tag, important)
Definition: src/core/lib/profiling/timers.h:43
grpc_call_stack_from_top_element
grpc_call_stack * grpc_call_stack_from_top_element(grpc_call_element *elem)
Definition: channel_stack.cc:276
AtomicError::get
grpc_error_handle get()
Definition: error.h:425
grpc_core::Call::GetPeer
virtual char * GetPeer()=0
grpc_core::CompressionAlgorithmSet::CompressionAlgorithmForLevel
grpc_compression_algorithm CompressionAlgorithmForLevel(grpc_compression_level level) const
Definition: compression_internal.cc:108
grpc_core
Definition: call_metric_recorder.h:31
grpc_core::FilterStackCall::ExternalRef
void ExternalRef() override
Definition: call.cc:205
grpc_core::FilterStackCall::incoming_compression_algorithm_
grpc_compression_algorithm incoming_compression_algorithm_
Definition: call.cc:388
grpc_core::FilterStackCall::receiving_stream_flags_
uint32_t receiving_stream_flags_
Definition: call.cc:399
setup.description
description
Definition: setup.py:544
grpc_core::MetadataMap::get_pointer
const metadata_detail::Value< Which >::StorageType * get_pointer(Which) const
Definition: metadata_batch.h:1039
grpc_metadata_array
Definition: grpc_types.h:579
grpc_transport_stream_op_batch::on_complete
grpc_closure * on_complete
Definition: transport.h:304
grpc_byte_buffer::grpc_byte_buffer_data::raw
struct grpc_byte_buffer::grpc_byte_buffer_data::grpc_compressed_buffer raw
grpc_core::FilterStackCall::received_final_op_atm_
gpr_atm received_final_op_atm_
Definition: call.cc:365
grpc_core::Slice
Definition: src/core/lib/slice/slice.h:282
grpc_core::MutexLock
Definition: src/core/lib/gprpp/sync.h:88
grpc_core::HttpPathMetadata
Definition: metadata_batch.h:262
grpc_core::channelz::ChannelNode::RecordCallFailed
void RecordCallFailed()
Definition: channelz.h:204
grpc_op::reserved
void * reserved
Definition: grpc_types.h:646
GPR_LIKELY
#define GPR_LIKELY(x)
Definition: impl/codegen/port_platform.h:769
grpc_call_stack_set_pollset_or_pollset_set
void grpc_call_stack_set_pollset_or_pollset_set(grpc_call_stack *call_stack, grpc_polling_entity *pollent)
Definition: channel_stack.cc:219
grpc_core::FilterStackCall::BatchControl::notify_tag
struct grpc_core::FilterStackCall::BatchControl::@33::@34 notify_tag
grpc_core::Call::ChildCall::sibling_prev
Call * sibling_prev
Definition: call.cc:139
grpc_compression_algorithm
grpc_compression_algorithm
Definition: compression_types.h:60
grpc_core::Call::PropagateCancellationToChildren
void PropagateCancellationToChildren()
Definition: call.cc:1051
grpc_core::done_termination
static void done_termination(void *arg, grpc_error_handle)
Definition: call.cc:758
grpc_core::slice_detail::StaticConstructors< StaticSlice >::FromStaticString
static StaticSlice FromStaticString(const char *s)
Definition: src/core/lib/slice/slice.h:201
GRPC_CALL_ERROR_NOT_ON_CLIENT
@ GRPC_CALL_ERROR_NOT_ON_CLIENT
Definition: grpc_types.h:472
grpc_core::FilterStackCall::GetPeer
char * GetPeer() override
Definition: call.cc:717
absl::string_view
Definition: abseil-cpp/absl/strings/string_view.h:167
grpc_core::FilterStackCall::BatchControl::op_
grpc_transport_stream_op_batch op_
Definition: call.cc:276
grpc_core::FilterStackCall::call_elem
grpc_call_element * call_elem(size_t idx)
Definition: call.cc:194
grpc_core::Timestamp
Definition: src/core/lib/gprpp/time.h:62
call_test_only.h
grpc_core::Call::InitParent
absl::Status InitParent(Call *parent, uint32_t propagation_mask)
Definition: call.cc:466
grpc_core::StringViewFromSlice
absl::string_view StringViewFromSlice(const grpc_slice &slice)
Definition: slice_internal.h:93
grpc_core::Arena::New
T * New(Args &&... args)
Definition: src/core/lib/resource_quota/arena.h:77
gpr_free
GPRAPI void gpr_free(void *ptr)
Definition: alloc.cc:51
grpc_core::FilterStackCall::stream_op_payload_
grpc_transport_stream_op_batch_payload stream_op_payload_
Definition: call.cc:368
testing::internal::string
::std::string string
Definition: bloaty/third_party/protobuf/third_party/googletest/googletest/include/gtest/internal/gtest-port.h:881
elem
Timer elem
Definition: event_engine/iomgr_event_engine/timer_heap_test.cc:109
grpc_core::GrpcMessageMetadata
Definition: metadata_batch.h:220
propagation_bits.h
error
grpc_error_handle error
Definition: retry_filter.cc:499
grpc_message
absl::optional< grpc_core::SliceBuffer > grpc_message
Definition: binder_transport_test.cc:310
GRPC_CALL_ERROR_COMPLETION_QUEUE_SHUTDOWN
@ GRPC_CALL_ERROR_COMPLETION_QUEUE_SHUTDOWN
Definition: grpc_types.h:498
grpc_status_code
grpc_status_code
Definition: include/grpc/impl/codegen/status.h:28
grpc_core::FilterStackCall::BatchControl::tag
void * tag
Definition: call.cc:292
grpc_core::GrpcEncodingMetadata
Definition: metadata_batch.h:175
gpr_atm_rel_cas
#define gpr_atm_rel_cas(p, o, n)
Definition: impl/codegen/atm_gcc_sync.h:76
completion_queue.h
grpc_call_final_info::stats
grpc_call_stats stats
Definition: channel_stack.h:96
UINT32_MAX
#define UINT32_MAX
Definition: stdint-msvc2008.h:142
arena.h
absl::debugging_internal::Append
static void Append(State *state, const char *const str, const int length)
Definition: abseil-cpp/absl/debugging/internal/demangle.cc:359
absl::OkStatus
Status OkStatus()
Definition: third_party/abseil-cpp/absl/status/status.h:882
gpr_malloc
GPRAPI void * gpr_malloc(size_t size)
Definition: alloc.cc:29
grpc_cq_completion
Definition: src/core/lib/surface/completion_queue.h:43
grpc_core::FilterStackCall::SetCompletionQueue
void SetCompletionQueue(grpc_completion_queue *cq) override
Definition: call.cc:624
grpc_core::Call::MaybeUnpublishFromParent
void MaybeUnpublishFromParent()
Definition: call.cc:671
grpc_core::FilterStackCall::BatchControl::PostCompletion
void PostCompletion()
Definition: call.cc:1071
u
OPENSSL_EXPORT pem_password_cb void * u
Definition: pem.h:351
grpc_channel_get_target
GRPCAPI char * grpc_channel_get_target(grpc_channel *channel)
Definition: channel.cc:256
GRPC_CALL_OK
@ GRPC_CALL_OK
Definition: grpc_types.h:466
grpc_core::Call::arena_
Arena *const arena_
Definition: call.cc:156
status
absl::Status status
Definition: rls.cc:251
GRPC_CONTEXT_COUNT
@ GRPC_CONTEXT_COUNT
Definition: core/lib/channel/context.h:48
grpc_core::FilterStackCall::cancelled
int * cancelled
Definition: call.cc:421
grpc_handler_private_op_data::extra_arg
void * extra_arg
Definition: transport.h:274
grpc_core::Call::test_only_encodings_accepted_by_peer
virtual uint32_t test_only_encodings_accepted_by_peer()=0
grpc_core::ApplicationCallbackExecCtx
Definition: exec_ctx.h:283
grpc_core::FilterStackCall::BatchControl::completed_batch_step
bool completed_batch_step()
Definition: call.cc:303
grpc_call_is_trailers_only
bool grpc_call_is_trailers_only(const grpc_call *call)
Definition: call.cc:1872
grpc_cq_end_op
void grpc_cq_end_op(grpc_completion_queue *cq, void *tag, grpc_error_handle error, void(*done)(void *done_arg, grpc_cq_completion *storage), void *done_arg, grpc_cq_completion *storage, bool internal)
Definition: completion_queue.cc:894
grpc_core::Call::ChildCall
Definition: call.cc:132
grpc_transport_stream_op_batch_payload::send_initial_metadata
grpc_metadata_batch * send_initial_metadata
Definition: transport.h:346
grpc_core::FilterStackCall::call_combiner_
CallCombiner call_combiner_
Definition: call.cc:348
grpc_call_stack_init
grpc_error_handle grpc_call_stack_init(grpc_channel_stack *channel_stack, int initial_refs, grpc_iomgr_cb_func destroy, void *destroy_arg, const grpc_call_element_args *elem_args)
Definition: channel_stack.cc:180
GRPC_LOG_IF_ERROR
#define GRPC_LOG_IF_ERROR(what, error)
Definition: error.h:398
grpc_compression_options
Definition: compression_types.h:80
check_documentation.path
path
Definition: check_documentation.py:57
grpc_core::FilterStackCall::BatchControl::completion_data_
union grpc_core::FilterStackCall::BatchControl::@33 completion_data_
grpc_core::FilterStackCall::sending_message_
bool sending_message_
Definition: call.cc:360
grpc_call_stack_element
grpc_call_element * grpc_call_stack_element(grpc_call_stack *call_stack, size_t index)
Definition: channel_stack.cc:100
grpc_core::Call::set_send_deadline
void set_send_deadline(Timestamp send_deadline)
Definition: call.cc:151
grpc_metadata_array::count
size_t count
Definition: grpc_types.h:580
GRPC_CLOSURE_CREATE
#define GRPC_CLOSURE_CREATE(cb, cb_arg, scheduler)
Definition: closure.h:160
grpc_core::GrpcAcceptEncodingMetadata
Definition: metadata_batch.h:187
GRPC_ERROR_CANCELLED
#define GRPC_ERROR_CANCELLED
Definition: error.h:238
grpc_call_element
Definition: channel_stack.h:194
GRPC_CALL_ERROR_INVALID_METADATA
@ GRPC_CALL_ERROR_INVALID_METADATA
Definition: grpc_types.h:487
grpc_is_binary_header_internal
int grpc_is_binary_header_internal(const grpc_slice &slice)
Definition: validate_metadata.cc:126
AtomicError::set
void set(grpc_error_handle error)
Definition: error.h:432
grpc_core::Call::parent_call_
std::atomic< ParentCall * > parent_call_
Definition: call.cc:157
channelz.h
uint8_t
unsigned char uint8_t
Definition: stdint-msvc2008.h:78
GRPC_CALL_ERROR_NOT_ON_SERVER
@ GRPC_CALL_ERROR_NOT_ON_SERVER
Definition: grpc_types.h:470
grpc_core::FilterStackCall::call_stack
grpc_call_stack * call_stack() override
Definition: call.cc:188
grpc_core::FilterStackCall::test_only_compression_algorithm
grpc_compression_algorithm test_only_compression_algorithm() override
Definition: call.cc:242
GRPC_COMPRESS_NONE
@ GRPC_COMPRESS_NONE
Definition: compression_types.h:61
grpc_core::TeMetadata
Definition: metadata_batch.h:71
grpc_core::FilterStackCall::buffered_metadata_
grpc_metadata_array * buffered_metadata_[2]
Definition: call.cc:378
grpc_core::Arena
Definition: src/core/lib/resource_quota/arena.h:45
grpc_core::FilterStackCall::kMaxConcurrentBatches
static constexpr size_t kMaxConcurrentBatches
Definition: call.cc:269
GRPC_TRACE_FLAG_ENABLED
#define GRPC_TRACE_FLAG_ENABLED(f)
Definition: debug/trace.h:114
grpc_core::Call::SetCompletionQueue
virtual void SetCompletionQueue(grpc_completion_queue *cq)=0
GRPC_CALL_LOG_OP
#define GRPC_CALL_LOG_OP(sev, elem, op)
Definition: channel_stack.h:374
stats.h
grpc_core::FilterStackCall::ReuseOrAllocateBatchControl
BatchControl * ReuseOrAllocateBatchControl(const grpc_op *ops)
Definition: call.cc:1029
grpc_op::grpc_op_data::recv_message
struct grpc_op::grpc_op_data::grpc_op_recv_message recv_message
grpc_call_error_trace
grpc_core::TraceFlag grpc_call_error_trace(false, "call_error")
grpc_core::FilterStackCall::channel_
RefCountedPtr< Channel > channel_
Definition: call.cc:351
grpc_core::channelz::ServerNode
Definition: channelz.h:239
call
FilterStackCall * call
Definition: call.cc:750
alloc.h
grpc_error_set_str
grpc_error_handle grpc_error_set_str(grpc_error_handle src, grpc_error_strs which, absl::string_view str)
Definition: error.cc:650
grpc_op::data
union grpc_op::grpc_op_data data
grpc_core::Call::~Call
~Call()=default
grpc_core::CallCombiner::Cancel
void Cancel(grpc_error_handle error)
Indicates that the call has been cancelled.
Definition: call_combiner.cc:255
grpc_core::Call::is_client
bool is_client() const
Definition: call.cc:89
status.h
grpc_core::FilterStackCall::receiving_buffer_
grpc_byte_buffer ** receiving_buffer_
Definition: call.cc:402
grpc_core::FilterStackCall::SetFinalStatus
void SetFinalStatus(grpc_error_handle error)
Definition: call.cc:797
grpc_call_start_batch
grpc_call_error grpc_call_start_batch(grpc_call *call, const grpc_op *ops, size_t nops, void *tag, void *reserved)
Definition: call.cc:1831
uint32_t
unsigned int uint32_t
Definition: stdint-msvc2008.h:80
grpc_core::FilterStackCall::sent_initial_metadata_
bool sent_initial_metadata_
Definition: call.cc:359
grpc_core::FilterStackCall::ContextGet
void * ContextGet(grpc_context_index elem) const override
Definition: call.cc:216
grpc_channel_stack::call_stack_size
size_t call_stack_size
Definition: channel_stack.h:208
grpc_call_get_call_stack
grpc_call_stack * grpc_call_get_call_stack(grpc_call *call)
Definition: call.cc:1827
grpc_core::MetadataMap::Remove
void Remove(Which)
Definition: metadata_batch.h:1087
grpc_core::FilterStackCall::ExternalUnref
void ExternalUnref() override
Definition: call.cc:690
grpc_core::Call::GetOrCreateParentCall
ParentCall * GetOrCreateParentCall()
Definition: call.cc:447
grpc_core::MetadataMap::TransportSize
size_t TransportSize() const
Definition: metadata_batch.h:1220
grpc_call_cancel_with_status
grpc_call_error grpc_call_cancel_with_status(grpc_call *c, grpc_status_code status, const char *description, void *reserved)
Definition: call.cc:1791
DEBUG_LOCATION
#define DEBUG_LOCATION
Definition: debug_location.h:41
grpc_op::grpc_op_data::grpc_op_recv_message::recv_message
struct grpc_byte_buffer ** recv_message
Definition: grpc_types.h:693
GPR_ROUND_UP_TO_ALIGNMENT_SIZE
#define GPR_ROUND_UP_TO_ALIGNMENT_SIZE(x)
Given a size, round up to the next multiple of sizeof(void*).
Definition: src/core/lib/gpr/alloc.h:25
string_util.h
grpc_metadata
Definition: grpc_types.h:537
context.h
GRPC_CALL_STACK_UNREF
#define GRPC_CALL_STACK_UNREF(call_stack, reason)
Definition: channel_stack.h:295
grpc_error_add_child
grpc_error_handle grpc_error_add_child(grpc_error_handle src, grpc_error_handle child)
Definition: error.cc:678
grpc_core::FilterStackCall::pollent_
grpc_polling_entity pollent_
Definition: call.cc:350
grpc_core::FilterStackCall::HandleCompressionAlgorithmDisabled
void HandleCompressionAlgorithmDisabled(grpc_compression_algorithm compression_algorithm) GPR_ATTRIBUTE_NOINLINE
Definition: call.cc:1177
grpc_core::Arena::CreateWithAlloc
static std::pair< Arena *, void * > CreateWithAlloc(size_t initial_size, size_t alloc_size, MemoryAllocator *memory_allocator)
Definition: src/core/lib/resource_quota/arena.cc:63
grpc_core::FilterStackCall::BatchControl::is_closure
bool is_closure
Definition: call.cc:293
grpc_transport_stream_op_batch::handler_private
grpc_handler_private_op_data handler_private
Definition: transport.h:338
channel
wrapped_grpc_channel * channel
Definition: src/php/ext/grpc/call.h:33
GRPC_STATS_INC_CLIENT_CALLS_CREATED
#define GRPC_STATS_INC_CLIENT_CALLS_CREATED()
Definition: stats_data.h:176
asyncio_get_stats.args
args
Definition: asyncio_get_stats.py:40
GRPC_STATUS_OK
@ GRPC_STATUS_OK
Definition: include/grpc/impl/codegen/status.h:30
grpc_core::SliceBuffer::Clear
void Clear()
Removes and unrefs all slices in the SliceBuffer.
Definition: src/core/lib/slice/slice_buffer.h:84
grpc_call_failed_before_recv_message
int grpc_call_failed_before_recv_message(const grpc_call *c)
Definition: call.cc:1876
GRPC_OP_RECV_INITIAL_METADATA
@ GRPC_OP_RECV_INITIAL_METADATA
Definition: grpc_types.h:617
grpc_core::RefCountedPtr
Definition: ref_counted_ptr.h:35
absl::move
constexpr absl::remove_reference_t< T > && move(T &&t) noexcept
Definition: abseil-cpp/absl/utility/utility.h:221
grpc_core::channelz::ServerNode::RecordCallStarted
void RecordCallStarted()
Definition: channelz.h:268
GPR_ASSERT
#define GPR_ASSERT(x)
Definition: include/grpc/impl/codegen/log.h:94
GRPC_CALL_ERROR_NOT_INVOKED
@ GRPC_CALL_ERROR_NOT_INVOKED
Definition: grpc_types.h:478
grpc_call_stats::transport_stream_stats
grpc_transport_stream_stats transport_stream_stats
Definition: channel_stack.h:91
gpr_realloc
GPRAPI void * gpr_realloc(void *p, size_t size)
Definition: alloc.cc:56
grpc_status
Definition: src/python/grpcio_status/grpc_status/__init__.py:1
grpc_core::FilterStackCall::BatchControl::ReceivingInitialMetadataReady
void ReceivingInitialMetadataReady(grpc_error_handle error)
Definition: call.cc:1221
int64_t
signed __int64 int64_t
Definition: stdint-msvc2008.h:89
GRPC_OP_SEND_STATUS_FROM_SERVER
@ GRPC_OP_SEND_STATUS_FROM_SERVER
Definition: grpc_types.h:612
grpc_call_get_initial_size_estimate
size_t grpc_call_get_initial_size_estimate()
Definition: call.cc:1754
grpc_polling_entity_pollset_set
grpc_pollset_set * grpc_polling_entity_pollset_set(grpc_polling_entity *pollent)
Definition: polling_entity.cc:49
absl::optional::has_value
constexpr bool has_value() const noexcept
Definition: abseil-cpp/absl/types/optional.h:461
gen_stats_data.c_str
def c_str(s, encoding='ascii')
Definition: gen_stats_data.py:38
GRPC_CALL_ERROR_INVALID_FLAGS
@ GRPC_CALL_ERROR_INVALID_FLAGS
Definition: grpc_types.h:485
tag
static void * tag(intptr_t t)
Definition: bad_client.cc:318
max
int max
Definition: bloaty/third_party/zlib/examples/enough.c:170
grpc_compression_algorithm_name
GRPCAPI int grpc_compression_algorithm_name(grpc_compression_algorithm algorithm, const char **name)
Definition: compression.cc:56
grpc_core::Call::arena
Arena * arena()
Definition: call.cc:88
grpc_core::CompressionAlgorithmSet::IsSet
bool IsSet(grpc_compression_algorithm algorithm) const
Definition: compression_internal.cc:190
grpc_core::SliceBuffer::c_slice_buffer
grpc_slice_buffer * c_slice_buffer()
Return a pointer to the back raw grpc_slice_buffer.
Definition: src/core/lib/slice/slice_buffer.h:117
grpc_op::grpc_op_data::grpc_op_send_status_from_server::status
grpc_status_code status
Definition: grpc_types.h:673
channel_stack.h
grpc_call_cancel
grpc_call_error grpc_call_cancel(grpc_call *call, void *reserved)
Definition: call.cc:1782
grpc_op::grpc_op_data::grpc_op_recv_status_on_client::error_string
const char ** error_string
Definition: grpc_types.h:707
grpc_core::HttpAuthorityMetadata
Definition: metadata_batch.h:256
grpc_core::Call::ExternalRef
virtual void ExternalRef()=0
grpc_core::Call::PublishToParent
void PublishToParent(Call *parent)
Definition: call.cc:499
slice
grpc_slice slice
Definition: src/core/lib/surface/server.cc:467
grpc_call_stack
Definition: channel_stack.h:233
grpc_core::Call::CancelWithStatus
void CancelWithStatus(grpc_status_code status, const char *description)
Definition: call.cc:788
grpc_core::FilterStackCall::BatchControl::ValidateFilteredMetadata
void ValidateFilteredMetadata()
Definition: call.cc:1198
gpr_log
GPRAPI void gpr_log(const char *file, int line, gpr_log_severity severity, const char *format,...) GPR_PRINT_FORMAT_CHECK(4
grpc_core::FilterStackCall::release_call_
grpc_closure release_call_
Definition: call.cc:412
grpc_core::FilterStackCall::BatchControl
Definition: call.cc:274
grpc_completion_queue
Definition: completion_queue.cc:347
grpc_polling_entity_create_from_pollset
grpc_polling_entity grpc_polling_entity_create_from_pollset(grpc_pollset *pollset)
Definition: polling_entity.cc:34
GPR_UNLIKELY
#define GPR_UNLIKELY(x)
Definition: impl/codegen/port_platform.h:770
grpc_op_type
grpc_op_type
Definition: grpc_types.h:593
grpc_core::FilterStackCall::is_trailers_only_
bool is_trailers_only_
Definition: call.cc:357
grpc_call_create_args
Definition: src/core/lib/surface/call.h:51
absl::UnknownError
Status UnknownError(absl::string_view message)
Definition: third_party/abseil-cpp/absl/status/status.cc:383
grpc_core::FilterStackCall::BatchControl::ReceivingTrailingMetadataReady
void ReceivingTrailingMetadataReady(grpc_error_handle error)
Definition: call.cc:1280
grpc.h
grpc_call
struct grpc_call grpc_call
Definition: grpc_types.h:70
gpr_atm_acq_load
#define gpr_atm_acq_load(p)
Definition: impl/codegen/atm_gcc_atomic.h:52
grpc_byte_buffer
Definition: grpc_types.h:43
grpc_core::FilterStackCall::send_initial_metadata_
grpc_metadata_batch send_initial_metadata_
Definition: call.cc:371
grpc_error_handle
grpc_error * grpc_error_handle
Definition: error.h:50
grpc_call_test_only_get_compression_algorithm
grpc_compression_algorithm grpc_call_test_only_get_compression_algorithm(grpc_call *call)
Definition: call.cc:1810
grpc_core::HostMetadata::key
static absl::string_view key()
Definition: metadata_batch.h:228
grpc_cq_pollset
grpc_pollset * grpc_cq_pollset(grpc_completion_queue *cq)
Definition: completion_queue.cc:1433
call_combiner.h
grpc_core::FilterStackCall::cq_
grpc_completion_queue * cq_
Definition: call.cc:349
GRPC_CALL_COMBINER_STOP
#define GRPC_CALL_COMBINER_STOP(call_combiner, reason)
Definition: call_combiner.h:58
GRPC_PROPAGATE_CENSUS_STATS_CONTEXT
#define GRPC_PROPAGATE_CENSUS_STATS_CONTEXT
Definition: propagation_bits.h:35
GRPC_COMPRESS_LEVEL_NONE
@ GRPC_COMPRESS_LEVEL_NONE
Definition: compression_types.h:73
grpc_core::RefCount::Unref
bool Unref()
Definition: ref_counted.h:152
absl::optional
Definition: abseil-cpp/absl/types/internal/optional.h:61
done
struct tab * done
Definition: bloaty/third_party/zlib/examples/enough.c:176
grpc_op
Definition: grpc_types.h:640
GRPC_OP_SEND_MESSAGE
@ GRPC_OP_SEND_MESSAGE
Definition: grpc_types.h:602
grpc_core::FilterStackCall::FilterStackCall
FilterStackCall(Arena *arena, const grpc_call_create_args &args)
Definition: call.cc:317
slice_buffer.h
arg
Definition: cmdline.cc:40
grpc_core::channelz::ServerNode::RecordCallSucceeded
void RecordCallSucceeded()
Definition: channelz.h:270
grpc_core::Call::ChildCall::parent
Call * parent
Definition: call.cc:134
grpc_transport_stream_op_batch::payload
grpc_transport_stream_op_batch_payload * payload
Definition: transport.h:307
cpp_impl_of.h
grpc_op::grpc_op_data::grpc_op_send_status_from_server::trailing_metadata
grpc_metadata * trailing_metadata
Definition: grpc_types.h:672
grpc_transport_stream_op_batch_payload::send_trailing_metadata
grpc_metadata_batch * send_trailing_metadata
Definition: transport.h:359
grpc_core::FilterStackCall::HandleCompressionAlgorithmNotAccepted
void HandleCompressionAlgorithmNotAccepted(grpc_compression_algorithm compression_algorithm) GPR_ATTRIBUTE_NOINLINE
Definition: call.cc:1187
grpc_empty_slice
GPRAPI grpc_slice grpc_empty_slice(void)
Definition: slice/slice.cc:42
gpr_atm_rel_store
#define gpr_atm_rel_store(p, value)
Definition: impl/codegen/atm_gcc_atomic.h:54
grpc_slice
Definition: include/grpc/impl/codegen/slice.h:65
GRPC_WRITE_USED_MASK
#define GRPC_WRITE_USED_MASK
Definition: grpc_types.h:517
GRPC_ERROR_STR_GRPC_MESSAGE
@ GRPC_ERROR_STR_GRPC_MESSAGE
grpc status message associated with this error
Definition: error.h:120
grpc_call_stack_destroy
void grpc_call_stack_destroy(grpc_call_stack *stack, const grpc_call_final_info *final_info, grpc_closure *then_schedule_closure)
Definition: channel_stack.cc:236
grpc_core::FilterStackCall
Definition: call.cc:165
grpc_core::Call::parent_call
ParentCall * parent_call()
Definition: call.cc:462
grpc_core::FilterStackCall::DestroyCall
static void DestroyCall(void *call, grpc_error_handle)
Definition: call.cc:645
grpc_call_error_to_string
const char * grpc_call_error_to_string(grpc_call_error error)
Definition: call.cc:1884
grpc_core::slice_detail::BaseSlice::as_string_view
absl::string_view as_string_view() const
Definition: src/core/lib/slice/slice.h:89
googletest-filter-unittest.child
child
Definition: bloaty/third_party/googletest/googletest/test/googletest-filter-unittest.py:62
intptr_t
_W64 signed int intptr_t
Definition: stdint-msvc2008.h:118
GRPC_STATS_INC_CALL_INITIAL_SIZE
#define GRPC_STATS_INC_CALL_INITIAL_SIZE(value)
Definition: stats_data.h:393
grpc_core::FilterStackCall::RecvInitialFilter
void RecvInitialFilter(grpc_metadata_batch *b)
Definition: call.cc:944
grpc_core::LbTokenMetadata::key
static absl::string_view key()
Definition: metadata_batch.h:345
grpc_core::CompressionAlgorithmSet::ToString
absl::string_view ToString() const
Definition: compression_internal.cc:207
grpc_core::FilterStackCall::BatchControl::finish_batch_
grpc_closure finish_batch_
Definition: call.cc:297
grpc_core::MetadataMap::Clear
void Clear()
Definition: metadata_batch.h:1214
gpr_atm_no_barrier_cas
#define gpr_atm_no_barrier_cas(p, o, n)
Definition: impl/codegen/atm_gcc_sync.h:74
grpc_polling_entity
Definition: polling_entity.h:38
grpc_core::Call::is_trailers_only
virtual bool is_trailers_only() const =0
grpc_call_element_args
Definition: channel_stack.h:80
grpc_core::Call::ChildCall::ChildCall
ChildCall(Call *parent)
Definition: call.cc:133
batch
grpc_transport_stream_op_batch * batch
Definition: retry_filter.cc:243
uintptr_t
_W64 unsigned int uintptr_t
Definition: stdint-msvc2008.h:119
slice_internal.h
GPR_ERROR
#define GPR_ERROR
Definition: include/grpc/impl/codegen/log.h:57
GPR_UNREACHABLE_CODE
#define GPR_UNREACHABLE_CODE(STATEMENT)
Definition: impl/codegen/port_platform.h:652
grpc_call_test_only_get_message_flags
uint32_t grpc_call_test_only_get_message_flags(grpc_call *call)
Definition: call.cc:1815
min
#define min(a, b)
Definition: qsort.h:83
b
uint64_t b
Definition: abseil-cpp/absl/container/internal/layout_test.cc:53
grpc_core::FilterStackCall::is_trailers_only
bool is_trailers_only() const override
Definition: call.cc:225
GRPC_CALL_COMBINER_START
#define GRPC_CALL_COMBINER_START(call_combiner, closure, error, reason)
Definition: call_combiner.h:56
GRPC_CONTEXT_TRACING
@ GRPC_CONTEXT_TRACING
Value is a census_context.
Definition: core/lib/channel/context.h:37
grpc_core::FilterStackCall::ContextSet
void ContextSet(grpc_context_index elem, void *value, void(*destroy)(void *value)) override
Definition: call.cc:1738
grpc_core::ExecCtx
Definition: exec_ctx.h:97
grpc_core::FilterStackCall::~FilterStackCall
~FilterStackCall()
Definition: call.cc:167
grpc_call_get_arena
grpc_core::Arena * grpc_call_get_arena(grpc_call *call)
Definition: call.cc:1823
grpc_call_compression_for_level
grpc_compression_algorithm grpc_call_compression_for_level(grpc_call *call, grpc_compression_level level)
Definition: call.cc:1867
grpc_core::GrpcStatusMetadata
Definition: metadata_batch.h:293
grpc_polling_entity_is_empty
bool grpc_polling_entity_is_empty(const grpc_polling_entity *pollent)
Definition: polling_entity.cc:57
tests.qps.qps_worker.dest
dest
Definition: qps_worker.py:45
Json::ValueType
ValueType
Type of the value held by a Value object.
Definition: third_party/bloaty/third_party/protobuf/conformance/third_party/jsoncpp/json.h:463
grpc_core::Call::ParentCall::ABSL_GUARDED_BY
Call *first_child ABSL_GUARDED_BY(child_list_mu)
setup.idx
idx
Definition: third_party/bloaty/third_party/capstone/bindings/python/setup.py:197
grpc_core::GrpcRetryPushbackMsMetadata::key
static absl::string_view key()
Definition: metadata_batch.h:309
grpc_core::FilterStackCall::BatchControl::ReceivingStreamReady
void ReceivingStreamReady(grpc_error_handle error)
Definition: call.cc:1156
grpc_op::op
grpc_op_type op
Definition: grpc_types.h:642
grpc_core::Arena::Destroy
size_t Destroy()
Definition: src/core/lib/resource_quota/arena.cc:73
GRPC_ERROR_CREATE_FROM_STATIC_STRING
#define GRPC_ERROR_CREATE_FROM_STATIC_STRING(desc)
Definition: error.h:291
grpc_core::channelz::ChannelNode::RecordCallSucceeded
void RecordCallSucceeded()
Definition: channelz.h:205
grpc_op::grpc_op_data::grpc_op_send_initial_metadata::count
size_t count
Definition: grpc_types.h:653
GRPC_SLICE_LENGTH
#define GRPC_SLICE_LENGTH(slice)
Definition: include/grpc/impl/codegen/slice.h:104
gpr_types.h
grpc_call_final_info::error_string
const char * error_string
Definition: channel_stack.h:98
grpc_core::TraceFlag
Definition: debug/trace.h:63
grpc_op::grpc_op_data::grpc_op_recv_status_on_client::status_details
grpc_slice * status_details
Definition: grpc_types.h:703
grpc_call_context_element::value
void * value
Definition: core/lib/channel/context.h:52
dest_
grpc_metadata_array *const dest_
Definition: call.cc:922
grpc_core::FilterStackCall::BatchControl::cq_completion
grpc_cq_completion cq_completion
Definition: call.cc:285
grpc_byte_buffer::data
union grpc_byte_buffer::grpc_byte_buffer_data data
grpc_core::channelz::ChannelNode
Definition: channelz.h:178
grpc_call_ref
void grpc_call_ref(grpc_call *c)
Definition: call.cc:1768
grpc_core::FilterStackCall::context_
grpc_call_context_element context_[GRPC_CONTEXT_COUNT]
Definition: call.cc:395
grpc_core::slice_detail::CopyConstructors< Slice >::FromInt64
static Slice FromInt64(int64_t i)
Definition: src/core/lib/slice/slice.h:192
grpc_make_transport_stream_op
grpc_transport_stream_op_batch * grpc_make_transport_stream_op(grpc_closure *on_complete)
Definition: transport.cc:230
value
const char * value
Definition: hpack_parser_table.cc:165
compression_internal.h
grpc_core::FilterStackCall::start_time_
gpr_cycle_counter start_time_
Definition: call.cc:352
grpc_core::Call::InternalRef
virtual void InternalRef(const char *reason)=0
grpc_core::FilterStackCall::encodings_accepted_by_peer_
CompressionAlgorithmSet encodings_accepted_by_peer_
Definition: call.cc:392
grpc_transport_stream_op_batch::recv_initial_metadata
bool recv_initial_metadata
Definition: transport.h:319
GRPC_STATS_INC_SERVER_CALLS_CREATED
#define GRPC_STATS_INC_SERVER_CALLS_CREATED()
Definition: stats_data.h:178
grpc_op::grpc_op_data::recv_close_on_server
struct grpc_op::grpc_op_data::grpc_op_recv_close_on_server recv_close_on_server
GRPC_OP_RECV_MESSAGE
@ GRPC_OP_RECV_MESSAGE
Definition: grpc_types.h:621
GRPC_CALL_ERROR_ALREADY_ACCEPTED
@ GRPC_CALL_ERROR_ALREADY_ACCEPTED
Definition: grpc_types.h:474
gpr_atm
intptr_t gpr_atm
Definition: impl/codegen/atm_gcc_atomic.h:32
grpc_transport_stream_op_batch_payload
Definition: transport.h:341
grpc_core::FilterStackCall::destroy_called_
bool destroy_called_
Definition: call.cc:355
grpc_core::Call::ExternalUnref
virtual void ExternalUnref()=0
grpc_call_is_client
uint8_t grpc_call_is_client(grpc_call *call)
Definition: call.cc:1863
grpc_cq_begin_op
bool grpc_cq_begin_op(grpc_completion_queue *cq, void *tag)
Definition: completion_queue.cc:672
grpc_core::channelz::ChannelNode::RecordCallStarted
void RecordCallStarted()
Definition: channelz.h:203
benchmark.md
md
Definition: benchmark.py:86
grpc_core::Mutex
Definition: src/core/lib/gprpp/sync.h:61
grpc_transport_stream_op_batch::send_trailing_metadata
bool send_trailing_metadata
Definition: transport.h:313
grpc_core::FilterStackCall::receiving_stream_ready_
grpc_closure receiving_stream_ready_
Definition: call.cc:404
grpc_core::Server
Definition: src/core/lib/surface/server.h:75
grpc_core::FilterStackCall::status_details
grpc_slice * status_details
Definition: call.cc:417
grpc_core::SliceBuffer
Definition: src/core/lib/slice/slice_buffer.h:44
grpc_core::FilterStackCall::compression_for_level
grpc_compression_algorithm compression_for_level(grpc_compression_level level) override
Definition: call.cc:220
GRPC_ERROR_REF
#define GRPC_ERROR_REF(err)
Definition: error.h:261
GRPC_WRITE_INTERNAL_COMPRESS
#define GRPC_WRITE_INTERNAL_COMPRESS
Definition: transport.h:75
absl_status_to_grpc_error
grpc_error_handle absl_status_to_grpc_error(absl::Status status)
Definition: error_utils.cc:167
debug_location.h
grpc_core::FilterStackCall::requested_final_op_
bool requested_final_op_
Definition: call.cc:364
grpc_call_context_get
void * grpc_call_context_get(grpc_call *call, grpc_context_index elem)
Definition: call.cc:1859
grpc_op::grpc_op_data::send_status_from_server
struct grpc_op::grpc_op_data::grpc_op_send_status_from_server send_status_from_server
grpc_call_context_set
void grpc_call_context_set(grpc_call *call, grpc_context_index elem, void *value, void(*destroy)(void *value))
Definition: call.cc:1854
key
const char * key
Definition: hpack_parser_table.cc:164
GRPC_WRITE_INTERNAL_USED_MASK
#define GRPC_WRITE_INTERNAL_USED_MASK
Definition: transport.h:81
grpc_core::GrpcInternalEncodingRequest
Definition: metadata_batch.h:181
grpc_transport_stream_op_batch::send_message
bool send_message
Definition: transport.h:316
GRPC_CALL_ERROR_PAYLOAD_TYPE_MISMATCH
@ GRPC_CALL_ERROR_PAYLOAD_TYPE_MISMATCH
Definition: grpc_types.h:496
grpc_error_set_int
grpc_error_handle grpc_error_set_int(grpc_error_handle src, grpc_error_ints which, intptr_t value)
Definition: error.cc:613
absl::flags_internal
Definition: abseil-cpp/absl/flags/commandlineflag.h:40
grpc_core::Call::failed_before_recv_message
virtual bool failed_before_recv_message() const =0
grpc_core::Call::test_only_compression_algorithm
virtual grpc_compression_algorithm test_only_compression_algorithm()=0
ref_counted.h
count
int * count
Definition: bloaty/third_party/googletest/googlemock/test/gmock_stress_test.cc:96
GRPC_OP_SEND_INITIAL_METADATA
@ GRPC_OP_SEND_INITIAL_METADATA
Definition: grpc_types.h:598
grpc_core::FilterStackCall::call_combiner
CallCombiner * call_combiner()
Definition: call.cc:198
start_batch
grpc_closure start_batch
Definition: call.cc:751
grpc_core::FilterStackCall::FromTopElem
static Call * FromTopElem(grpc_call_element *elem)
Definition: call.cc:184
grpc_core::FilterStackCall::BatchControl::call_
FilterStackCall * call_
Definition: call.cc:275
exec_ctx
grpc_core::ExecCtx exec_ctx
Definition: end2end_binder_transport_test.cc:75
grpc_error_std_string
std::string grpc_error_std_string(grpc_error_handle error)
Definition: error.cc:944
grpc_op::grpc_op_data::send_message
struct grpc_op::grpc_op_data::grpc_op_send_message send_message
grpc_core::FilterStackCall::recv_initial_metadata_
grpc_metadata_batch recv_initial_metadata_
Definition: call.cc:373
absl::Status
Definition: third_party/abseil-cpp/absl/status/status.h:424
validate_metadata.h
gpr_cycle_counter_sub
gpr_timespec gpr_cycle_counter_sub(gpr_cycle_counter a, gpr_cycle_counter b)
grpc_core::FilterStackCall::Create
static grpc_error_handle Create(grpc_call_create_args *args, grpc_call **out_call)
Definition: call.cc:517
grpc_call_get_peer
char * grpc_call_get_peer(grpc_call *call)
Definition: call.cc:1774
grpc_core::FilterStackCall::send_slice_buffer_
SliceBuffer send_slice_buffer_
Definition: call.cc:397
GRPC_ERROR_CREATE_FROM_CPP_STRING
#define GRPC_ERROR_CREATE_FROM_CPP_STRING(desc)
Definition: error.h:297
grpc_core::Call::ParentCall::child_list_mu
Mutex child_list_mu
Definition: call.cc:128
grpc_byte_buffer::grpc_byte_buffer_data::grpc_compressed_buffer::compression
grpc_compression_algorithm compression
Definition: grpc_types.h:51
GRPC_PROPAGATE_CENSUS_TRACING_CONTEXT
#define GRPC_PROPAGATE_CENSUS_TRACING_CONTEXT
Definition: propagation_bits.h:36
alloc.h
grpc_op::grpc_op_data::grpc_op_send_initial_metadata::metadata
grpc_metadata * metadata
Definition: grpc_types.h:654
grpc_core::Call::ParentCall
Definition: call.cc:127
GRPC_CALL_ERROR_BATCH_TOO_BIG
@ GRPC_CALL_ERROR_BATCH_TOO_BIG
Definition: grpc_types.h:494
grpc_op::grpc_op_data::recv_status_on_client
struct grpc_op::grpc_op_data::grpc_op_recv_status_on_client recv_status_on_client
grpc_compression_level
grpc_compression_level
Definition: compression_types.h:72
grpc_op::grpc_op_data::grpc_op_send_status_from_server::trailing_metadata_count
size_t trailing_metadata_count
Definition: grpc_types.h:671
grpc_op::grpc_op_data::grpc_op_send_initial_metadata::maybe_compression_level
struct grpc_op::grpc_op_data::grpc_op_send_initial_metadata::grpc_op_send_initial_metadata_maybe_compression_level maybe_compression_level
grpc_core::FilterStackCall::sent_server_trailing_metadata_
bool sent_server_trailing_metadata_
Definition: call.cc:409
grpc_core::FilterStackCall::server
struct grpc_core::FilterStackCall::@32::@36 server
grpc_transport_stream_op_batch_payload::send_message
grpc_core::SliceBuffer * send_message
Definition: transport.h:373
grpc_call_context_element
Definition: core/lib/channel/context.h:51
grpc_core::Call::StartBatch
virtual grpc_call_error StartBatch(const grpc_op *ops, size_t nops, void *notify_tag, bool is_notify_tag_closure)=0
GRPC_CQ_INTERNAL_UNREF
#define GRPC_CQ_INTERNAL_UNREF(cq, reason)
Definition: src/core/lib/surface/completion_queue.h:65
grpc_transport_stream_op_batch_payload::recv_initial_metadata
grpc_metadata_batch * recv_initial_metadata
Definition: transport.h:390
grpc_core::FilterStackCall::cancelled_with_error_
gpr_atm cancelled_with_error_
Definition: call.cc:410
grpc_byte_buffer_destroy
GRPCAPI void grpc_byte_buffer_destroy(grpc_byte_buffer *bb)
Definition: byte_buffer.cc:81
grpc_core::FilterStackCall::test_only_encodings_accepted_by_peer
uint32_t test_only_encodings_accepted_by_peer() override
Definition: call.cc:250
grpc_core::FilterStackCall::test_only_last_message_flags_
uint32_t test_only_last_message_flags_
Definition: call.cc:407
grpc_core::FilterStackCall::BatchControl::FinishBatch
void FinishBatch(grpc_error_handle error)
Definition: call.cc:1289
grpc_core::FilterStackCall::Completed
bool Completed() override
Definition: call.cc:176
grpc_transport_stream_op_batch::send_initial_metadata
bool send_initial_metadata
Definition: transport.h:310
grpc_validate_header_key_is_legal
grpc_error_handle grpc_validate_header_key_is_legal(const grpc_slice &slice)
Definition: validate_metadata.cc:83
arg
struct arg arg
grpc_core::Call::CancelWithError
virtual void CancelWithError(grpc_error_handle error)=0
state
Definition: bloaty/third_party/zlib/contrib/blast/blast.c:41
grpc_transport_stream_op_batch_payload::recv_message
absl::optional< grpc_core::SliceBuffer > * recv_message
Definition: transport.h:416
exec_ctx.h
grpc_op::grpc_op_data::grpc_op_send_initial_metadata::grpc_op_send_initial_metadata_maybe_compression_level::is_set
uint8_t is_set
Definition: grpc_types.h:658
grpc_core::FilterStackCall::final_op_
union grpc_core::FilterStackCall::@32 final_op_
grpc_call_test_only_get_encodings_accepted_by_peer
uint32_t grpc_call_test_only_get_encodings_accepted_by_peer(grpc_call *call)
Definition: call.cc:1819
grpc_slice_from_cpp_string
grpc_slice grpc_slice_from_cpp_string(std::string str)
Definition: slice/slice.cc:202
AtomicError::ok
bool ok()
returns get() == GRPC_ERROR_NONE
Definition: error.h:418
server.h
slice_refcount.h
grpc_core::Arena::Alloc
void * Alloc(size_t size)
Definition: src/core/lib/resource_quota/arena.h:60
closure
Definition: proxy.cc:59
grpc_core::FilterStackCall::status_error_
AtomicError status_error_
Definition: call.cc:426
grpc_core::FilterStackCall::final_info_
grpc_call_final_info final_info_
Definition: call.cc:385
GRPC_CQ_INTERNAL_REF
#define GRPC_CQ_INTERNAL_REF(cq, reason)
Definition: src/core/lib/surface/completion_queue.h:63
GRPC_ERROR_UNREF
#define GRPC_ERROR_UNREF(err)
Definition: error.h:262
grpc_core::FilterStackCall::receiving_trailing_metadata_ready_
grpc_closure receiving_trailing_metadata_ready_
Definition: call.cc:406
grpc_core::FilterStackCall::sent_final_op_
bool sent_final_op_
Definition: call.cc:361
transport.h
grpc_core::Call::test_only_message_flags
virtual uint32_t test_only_message_flags()=0
grpc_byte_buffer::grpc_byte_buffer_data::grpc_compressed_buffer::slice_buffer
grpc_slice_buffer slice_buffer
Definition: grpc_types.h:52
grpc_call_context_element::destroy
void(* destroy)(void *)
Definition: core/lib/channel/context.h:53
grpc_core::FilterStackCall::recv_state_
gpr_atm recv_state_
Definition: call.cc:444
grpc_core::Call::send_deadline_
Timestamp send_deadline_
Definition: call.cc:159
cancel
bool cancel
Definition: client_callback_end2end_test.cc:634
GRPC_OP_RECV_CLOSE_ON_SERVER
@ GRPC_OP_RECV_CLOSE_ON_SERVER
Definition: grpc_types.h:633
grpc_call_server_authority
absl::string_view grpc_call_server_authority(const grpc_call *call)
Definition: call.cc:1880
GRPC_STATUS_UNIMPLEMENTED
@ GRPC_STATUS_UNIMPLEMENTED
Definition: include/grpc/impl/codegen/status.h:124
grpc_core::FilterStackCall::receiving_slice_
grpc_slice receiving_slice_
Definition: call.cc:403
grpc_core::Call::ChildCall::sibling_next
Call * sibling_next
Definition: call.cc:138
grpc_core::FilterStackCall::recv_trailing_metadata_
grpc_metadata_batch recv_trailing_metadata_
Definition: call.cc:374
api_trace.h
grpc_transport_stream_op_batch::recv_trailing_metadata
bool recv_trailing_metadata
Definition: transport.h:326
grpc_core::FilterStackCall::PublishAppMetadata
void PublishAppMetadata(grpc_metadata_batch *b, bool is_trailing)
Definition: call.cc:926
grpc_core::CompressionAlgorithmSet::FromUint32
static CompressionAlgorithmSet FromUint32(uint32_t value)
Definition: compression_internal.cc:155
finish_batch
grpc_closure finish_batch
Definition: call.cc:752
gpr_strdup
GPRAPI char * gpr_strdup(const char *src)
Definition: string.cc:39
GRPC_CALL_ERROR_ALREADY_FINISHED
@ GRPC_CALL_ERROR_ALREADY_FINISHED
Definition: grpc_types.h:481
grpc_core::FilterStackCall::InternalUnref
void InternalUnref(const char *reason) override
Definition: call.cc:210
GPR_DEBUG
#define GPR_DEBUG
Definition: include/grpc/impl/codegen/log.h:55
grpc_core::FilterStackCall::BatchControl::FinishStep
void FinishStep()
Definition: call.cc:1126
grpc_core::Call::ContextSet
virtual void ContextSet(grpc_context_index elem, void *value, void(*destroy)(void *value))=0
grpc_error_get_status
void grpc_error_get_status(grpc_error_handle error, grpc_core::Timestamp deadline, grpc_status_code *code, std::string *message, grpc_http2_error_code *http_error, const char **error_string)
Definition: error_utils.cc:67
grpc_core::FilterStackCall::send_trailing_metadata_
grpc_metadata_batch send_trailing_metadata_
Definition: call.cc:372
grpc_call_start_batch_and_execute
grpc_call_error grpc_call_start_batch_and_execute(grpc_call *call, const grpc_op *ops, size_t nops, grpc_closure *closure)
Definition: call.cc:1847
Duration
Definition: bloaty/third_party/protobuf/src/google/protobuf/duration.pb.h:69
grpc_core::FilterStackCall::InternalRef
void InternalRef(const char *reason) override
Definition: call.cc:207
grpc_core::Timestamp::InfFuture
static constexpr Timestamp InfFuture()
Definition: src/core/lib/gprpp/time.h:79
flags
uint32_t flags
Definition: retry_filter.cc:632
grpc_core::channelz::ServerNode::RecordCallFailed
void RecordCallFailed()
Definition: channelz.h:269
grpc_core::CppImplOf::c_ptr
CType * c_ptr()
Definition: cpp_impl_of.h:39
atm.h
grpc_core::GrpcPreviousRpcAttemptsMetadata::key
static absl::string_view key()
Definition: metadata_batch.h:303
grpc_op::grpc_op_data::recv_initial_metadata
struct grpc_op::grpc_op_data::grpc_op_recv_initial_metadata recv_initial_metadata
grpc_call_final_info
Definition: channel_stack.h:95
grpc_transport_stream_op_batch_payload::recv_trailing_metadata
grpc_metadata_batch * recv_trailing_metadata
Definition: transport.h:425
grpc_op::grpc_op_data::grpc_op_send_status_from_server::status_details
grpc_slice * status_details
Definition: grpc_types.h:677
client.level
level
Definition: examples/python/async_streaming/client.py:118
GRPC_PROPAGATE_DEADLINE
#define GRPC_PROPAGATE_DEADLINE
Definition: propagation_bits.h:33
grpc_core::UserAgentMetadata::key
static absl::string_view key()
Definition: metadata_batch.h:216
asyncio_get_stats.type
type
Definition: asyncio_get_stats.py:37
grpc_core::FilterStackCall::receiving_initial_metadata_ready_
grpc_closure receiving_initial_metadata_ready_
Definition: call.cc:405
grpc_core::FilterStackCall::kRecvNone
static constexpr gpr_atm kRecvNone
Definition: call.cc:271
grpc_error
Definition: error_internal.h:42
grpc_core::Call::Completed
virtual bool Completed()=0
grpc_core::FilterStackCall::BatchControl::set_num_steps_to_complete
void set_num_steps_to_complete(uintptr_t steps)
Definition: call.cc:300
grpc_polling_entity_create_from_pollset_set
grpc_polling_entity grpc_polling_entity_create_from_pollset_set(grpc_pollset_set *pollset_set)
Definition: polling_entity.cc:26
grpc_core::FilterStackCall::RecvTrailingFilter
void RecvTrailingFilter(grpc_metadata_batch *b, grpc_error_handle batch_error)
Definition: call.cc:953
size
voidpf void uLong size
Definition: bloaty/third_party/zlib/contrib/minizip/ioapi.h:136
GRPC_OP_RECV_STATUS_ON_CLIENT
@ GRPC_OP_RECV_STATUS_ON_CLIENT
Definition: grpc_types.h:627
grpc_op::grpc_op_data::grpc_op_recv_initial_metadata::recv_initial_metadata
grpc_metadata_array * recv_initial_metadata
Definition: grpc_types.h:685
GRPC_CALL_STACK_REF
#define GRPC_CALL_STACK_REF(call_stack, reason)
Definition: channel_stack.h:293
grpc_core::FilterStackCall::active_batches_
BatchControl * active_batches_[kMaxConcurrentBatches]
Definition: call.cc:367
grpc_core::FilterStackCall::CancelWithError
void CancelWithError(grpc_error_handle error) override
Definition: call.cc:766
grpc_core::FilterStackCall::BatchControl::ProcessDataAfterMetadata
void ProcessDataAfterMetadata()
Definition: call.cc:1132
testing::Ref
internal::RefMatcher< T & > Ref(T &x)
Definition: cares/cares/test/gmock-1.8.0/gmock/gmock.h:8628
grpc_core::CppImplOf< Call, grpc_call >::FromC
static Call * FromC(grpc_call *c_type)
Definition: cpp_impl_of.h:30
grpc_core::FilterStackCall::kRecvInitialMetadataFirst
static constexpr gpr_atm kRecvInitialMetadataFirst
Definition: call.cc:272
grpc_slice_str_cmp
GPRAPI int grpc_slice_str_cmp(grpc_slice a, const char *b)
Definition: slice/slice.cc:426
grpc_metadata_batch
Definition: metadata_batch.h:1259
grpc_context_index
grpc_context_index
Call object context pointers.
Definition: core/lib/channel/context.h:31
grpc_core::CompressionAlgorithmSet::ToLegacyBitmask
uint32_t ToLegacyBitmask() const
Definition: compression_internal.cc:228
grpc_core::Call::ContextGet
virtual void * ContextGet(grpc_context_index elem) const =0
grpc_call_unref
void grpc_call_unref(grpc_call *c)
Definition: call.cc:1770
grpc_transport_stream_op_batch
Definition: transport.h:284
grpc_core::RefCount
Definition: ref_counted.h:44
grpc_closure
Definition: closure.h:56
op
static grpc_op * op
Definition: test/core/fling/client.cc:47
grpc_core::Call::call_stack
virtual grpc_call_stack * call_stack()=0
slice_buffer.h
ops
static grpc_op ops[6]
Definition: test/core/fling/client.cc:39
grpc_core::FilterStackCall::call_failed_before_recv_message_
bool call_failed_before_recv_message_
Definition: call.cc:401
GRPC_CALL_ERROR_NOT_SERVER_COMPLETION_QUEUE
@ GRPC_CALL_ERROR_NOT_SERVER_COMPLETION_QUEUE
Definition: grpc_types.h:492
grpc_call_from_top_element
grpc_call * grpc_call_from_top_element(grpc_call_element *surface_element)
Definition: call.cc:1778
grpc_core::FilterStackCall::failed_before_recv_message
bool failed_before_recv_message() const override
Definition: call.cc:231
grpc_core::FilterStackCall::FromCallStack
static FilterStackCall * FromCallStack(grpc_call_stack *call_stack)
Definition: call.cc:326
grpc_core::Closure::Run
static void Run(const DebugLocation &location, grpc_closure *closure, grpc_error_handle error)
Definition: closure.h:250
grpc_core::FilterStackCall::StartBatch
grpc_call_error StartBatch(const grpc_op *ops, size_t nops, void *notify_tag, bool is_notify_tag_closure) override
Definition: call.cc:1300
grpc_core::Call::send_deadline
Timestamp send_deadline() const
Definition: call.cc:150
grpc_core::CppImplOf
Definition: cpp_impl_of.h:27
grpc_op::grpc_op_data::grpc_op_recv_close_on_server::cancelled
int * cancelled
Definition: grpc_types.h:714
cq
static grpc_completion_queue * cq
Definition: test/core/fling/client.cc:37
grpc_core::Call::compression_for_level
virtual grpc_compression_algorithm compression_for_level(grpc_compression_level level)=0
grpc_core::FilterStackCall::peer_string_
gpr_atm peer_string_
Definition: call.cc:381
grpc_core::Call::child_
ChildCall * child_
Definition: call.cc:158
sync.h
grpc_core::FilterStackCall::test_only_message_flags
uint32_t test_only_message_flags() override
Definition: call.cc:246
grpc_metadata::key
grpc_slice key
Definition: grpc_types.h:540
destroy
static std::function< void(void *, Slot *)> destroy
Definition: abseil-cpp/absl/container/internal/hash_policy_traits_test.cc:42
GRPC_INITIAL_METADATA_USED_MASK
#define GRPC_INITIAL_METADATA_USED_MASK
Definition: grpc_types.h:531
call.h
GRPC_OP_SEND_CLOSE_FROM_CLIENT
@ GRPC_OP_SEND_CLOSE_FROM_CLIENT
Definition: grpc_types.h:607
GPR_ATTRIBUTE_NOINLINE
#define GPR_ATTRIBUTE_NOINLINE
Definition: impl/codegen/port_platform.h:684
i
uint64_t i
Definition: abseil-cpp/absl/container/btree_benchmark.cc:230
GRPC_ERROR_INT_GRPC_STATUS
@ GRPC_ERROR_INT_GRPC_STATUS
grpc status code representing this error
Definition: error.h:66
grpc_core::FilterStackCall::BatchControl::start_batch_
grpc_closure start_batch_
Definition: call.cc:296
state
static struct rpc_state state
Definition: bad_server_response_test.cc:87
GRPC_API_TRACE
#define GRPC_API_TRACE(fmt, nargs, args)
Definition: api_trace.h:48
GRPC_STATUS_UNKNOWN
@ GRPC_STATUS_UNKNOWN
Definition: include/grpc/impl/codegen/status.h:40
grpc_slice_unref_internal
void grpc_slice_unref_internal(const grpc_slice &slice)
Definition: slice_refcount.h:39
grpc_core::FilterStackCall::client
struct grpc_core::FilterStackCall::@32::@35 client
error_utils.h
grpc_core::FilterStackCall::ExecuteBatch
void ExecuteBatch(grpc_transport_stream_op_batch *batch, grpc_closure *start_batch_closure)
Definition: call.cc:727
GRPC_ERROR_IS_NONE
#define GRPC_ERROR_IS_NONE(err)
Definition: error.h:241
channel.h
grpc_slice_copy
GPRAPI grpc_slice grpc_slice_copy(grpc_slice s)
Definition: slice/slice.cc:46
time_precise.h
port_platform.h
GRPC_PROPAGATE_CANCELLATION
#define GRPC_PROPAGATE_CANCELLATION
Definition: propagation_bits.h:38
grpc_call_cancel_internal
void grpc_call_cancel_internal(grpc_call *call)
Definition: call.cc:1806
grpc_core::FilterStackCall::InitialSizeEstimate
static size_t InitialSizeEstimate()
Definition: call.cc:254


grpc
Author(s):
autogenerated on Thu Mar 13 2025 02:58:42